From d9427c61125ad770a2a60ab9776a2a626adffe85 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Fri, 16 Sep 2022 14:13:41 +0200 Subject: [PATCH 001/101] added AcsParameters --- mission/controller/acs/AcsParameters.cpp | 128 +++++++++++++++ mission/controller/acs/AcsParameters.h | 201 +++++++++++++++++++++++ 2 files changed, 329 insertions(+) create mode 100644 mission/controller/acs/AcsParameters.cpp create mode 100644 mission/controller/acs/AcsParameters.h diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp new file mode 100644 index 00000000..91090028 --- /dev/null +++ b/mission/controller/acs/AcsParameters.cpp @@ -0,0 +1,128 @@ +#include +#include "AcsParameters.h" + +#include +#include + +AcsParameters::AcsParameters() { + + onBoardParams.sampleTime = 0.1; + + inertiaEIVE.inertiaMatrix = {{ 1, 0, 0}, + { 0, 1, 0}, + { 0,0.5, 1}}; + + mgmHandlingParameters.mgm0orientationMatrix = {{ 0, 0,-1}, + { 0, 1, 0}, + { 1, 0, 0}}; + /*mgmHandlingParameters.mgm1orientationMatrix = {{ 0, 0, 1}, + { 0,-1, 0}, + { 1, 0, 0}}; + mgmHandlingParameters.mgm2orientationMatrix = {{ 0, 0,-1}, + { 0, 1, 0}, + { 1 ,0, 0}}; + mgmHandlingParameters.mgm3orientationMatrix = {{ 0, 0, 1}, + { 0,-1, 0}, + { 1, 0, 0}}; + mgmHandlingParameters.mgm4orientationMatrix = {{ 0, 0,-1}, + {-1, 0, 0}, + { 0, 1, 0}};*/ + + rwHandlingParameters.inertiaWheel = 0.000028198; + rwHandlingParameters.maxTrq = 0.0032; //3.2 [mNm] + + //Geometry frame + rwMatrices.alignmentMatrix = {{ 0.9205, 0,-0.9205, 0}, + { 0,-0.9205, 0, 0.9205}, + { 0.3907, 0.3907, 0.3907, 0.3907}}; + + rwMatrices.pseudoInverse = {{ 0.4434,-0.2845, 0.3597}, + { 0.2136,-0.3317, 1.0123}, + {-0.8672,-0.1406, 0.1778}, + { 0.6426, 0.4794, 1.3603}}; + + rwMatrices.nullspace = {-0.7358, 0.5469,-0.3637,-0.1649}; + + kalmanFilterParameters.sensorNoiseSS = 8 * Math::PI / 180; + kalmanFilterParameters.sensorNoiseMAG = 4 * Math::PI / 180; + kalmanFilterParameters.sensorNoiseSTR = 0.1 * Math::PI / 180; + + sunModelParameters.domega = 36000.771; + sunModelParameters.omega_0 = 282.94 * Math::PI / 180.; + sunModelParameters.dm = 35999.049; + sunModelParameters.m_0 = 357.5256; + sunModelParameters.e = 23.4392911 * Math::PI / 180.; + sunModelParameters.e = 0.74508 * Math::PI / 180.; + sunModelParameters.p1 = 6892. / 3600. * Math::PI / 180.; + sunModelParameters.p2 = 72. / 3600. * Math::PI / 180.; + + safeModeControllerParameters.k_rate_mekf = 0.00059437; + safeModeControllerParameters.k_align_mekf = 0.000056875; + + safeModeControllerParameters.sunTargetDir = {1,0,0}; + + detumbleCtrlParameters.gainD = pow(10.0,-3.3); + + // Stuttgart + groundStationParameters.latitudeGs = 48.7495 * Math::PI / 180.; + groundStationParameters.longitudeGs = 9.10384 * Math::PI / 180.; + groundStationParameters.altitudeGs = 500; + + groundStationParameters.earthRadiusEquat = 6378137; + groundStationParameters.earthRadiusPolar = 6356752.314; + +// Geometry frame + targetModeControllerParameters.refDirection = {1,0,0}; + targetModeControllerParameters.refRotRate = {0,0,0}; + targetModeControllerParameters.quatRef = {0,0,0,1}; + + targetModeControllerParameters.avoidBlindStr = true; + targetModeControllerParameters.blindAvoidStart = 1.5; + targetModeControllerParameters.blindAvoidStop = 2.5; + targetModeControllerParameters.blindRotRate = 1 * Math::PI /180; + + targetModeControllerParameters.zeta = 0.3; + targetModeControllerParameters.om = 0.3; + targetModeControllerParameters.qiMin = 0.1; + targetModeControllerParameters.omMax = 1 * Math::PI / 180; + targetModeControllerParameters.gainNullspace = 0.01; + + targetModeControllerParameters.desatMomentumRef = {0,0,0}; + targetModeControllerParameters.deSatGainFactor = 1000; + targetModeControllerParameters.desatOn = true; + + targetModeControllerParameters.omegaEarth = 0.000072921158553; + + strParameters.boresightAxis = { 0.7593, 0,-0.6508}; + strParameters.exclusionAngle = 20 * Math::PI /180; + + magnetorquesParameter.mtq0orientationMatrix = {{ 1, 0, 0}, + { 0, 0, 1}, + { 0,-1, 0}}; + magnetorquesParameter.mtq1orientationMatrix = {{ 1, 0, 0}, + { 0, 1, 0}, + { 0, 0, 1}}; + magnetorquesParameter.mtq2orientationMatrix = {{ 0, 0, 1}, + { 0, 1, 0}, + {-1, 0, 0}}; + magnetorquesParameter.alignmentMatrixMtq = {{ 0, 0,-1}, + {-1, 0, 0}, + { 0, 1, 0}}; + magnetorquesParameter.inverseAlignment = {{ 0,-1, 0}, + { 0, 0, 1}, + {-1, 0, 0}}; + magnetorquesParameter.DipolMax = 0.2; + +} + +AcsParameters::~AcsParameters() { +} + +/* +ReturnValue_t AcsParameters::getParameter(uint8_t domainId, + uint16_t parameterId, ParameterWrapper* parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex) { + + return 0; + +}*/ diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h new file mode 100644 index 00000000..b4e32d65 --- /dev/null +++ b/mission/controller/acs/AcsParameters.h @@ -0,0 +1,201 @@ +/******************************* + * EIVE Flight Software Framework (FSFW) + * (c) 2022 IRS, Uni Stuttgart + *******************************/ + +#ifndef ACSPARAMETERS_H_ +#define ACSPARAMETERS_H_ + +#include + +typedef unsigned char uint8_t; + +class AcsParameters:public HasParametersIF{ +public: + + AcsParameters(); + virtual ~AcsParameters(); + + virtual ReturnValue_t getParameter(uint8_t domainId, uint16_t parameterId, + ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex); + + struct OnBoardParams { + double sampleTime; // [s] + } onBoardParams; + + struct InertiaEIVE { + double inertiaMatrix[3][3]; + double inertiaMatrixInverse[3][3]; + } inertiaEIVE; + + struct MgmHandlingParameters { + float mgm0orientationMatrix[3][3]; + float mgm1orientationMatrix[3][3]; + float mgm2orientationMatrix[3][3]; + float mgm3orientationMatrix[3][3]; + float mgm4orientationMatrix[3][3]; + } mgmHandlingParameters; + + struct SusHandlingParameters { + float sus0orientationMatrix[3][3]; + float sus1orientationMatrix[3][3]; + float sus2orientationMatrix[3][3]; + float sus3orientationMatrix[3][3]; + float sus4orientationMatrix[3][3]; + float sus5orientationMatrix[3][3]; + float sus6orientationMatrix[3][3]; + float sus7orientationMatrix[3][3]; + float sus8orientationMatrix[3][3]; + float sus9orientationMatrix[3][3]; + float sus10orientationMatrix[3][3]; + float sus11orientationMatrix[3][3]; + + float filterAlpha; + float sunThresh; + } susHandlingParameters; + + struct RmuHandlingParameters { + double rmu0orientationMatrix[3][3]; + double rmu1orientationMatrix[3][3]; + double rmu2orientationMatrix[3][3]; + } rmuHandlingParameters; + + struct RwHandlingParameters { + double rw0orientationMatrix[3][3]; + double rw1orientationMatrix[3][3]; + double rw2orientationMatrix[3][3]; + double rw3orientationMatrix[3][3]; + double inertiaWheel; + double maxTrq; + } rwHandlingParameters; + + struct SafeModeControllerParameters { + double k_rate_mekf; + double k_align_mekf; + + double k_rate_no_mekf; + double k_align_no_mekf; + double sunMagAngleMin; + + double sunTargetDir[3]; //Body frame + double satRateRef[3]; //Body frame + + } safeModeControllerParameters; + + struct DetumbleCtrlParameters { + + double gainD; + + } detumbleCtrlParameters; + + + struct PointingModeControllerParameters { + double updtFlag; + double A_rw[3][12]; + + double refDirection[3]; + double refRotRate[3]; + double quatRef[4]; + bool avoidBlindStr; + double blindAvoidStart; + double blindAvoidStop; + double blindRotRate; + + double zeta; + double zetaLow; + double om; + double omLow; + double qiMin; + double omMax; + double gainNullspace; + + double desatMomentumRef[3]; + double deSatGainFactor; + bool desatOn; + + double omegaEarth; + + + } inertialModeControllerParameters, nadirModeControllerParameters, + targetModeControllerParameters; + + + struct RWMatrices { + double alignmentMatrix[3][4]; + double pseudoInverse[4][3]; + double without0[4][3]; + double without1[4][3]; + double without2[4][3]; + double without3[4][3]; + double nullspace[4]; + } rwMatrices; + + struct StrParameters { + double exclusionAngle; +// double strOrientationMatrix[3][3]; + double boresightAxis[3]; //in body/geometry frame + } strParameters; + + struct GpsParameters { + } gpsParameters; + + struct GroundStationParameters { + double latitudeGs; // [rad] Latitude + double longitudeGs; // [rad] Longitude + double altitudeGs; // [m] Altitude + double earthRadiusEquat; // [m] + double earthRadiusPolar; // [m] + } groundStationParameters; + + struct SunModelParameters { + enum UseSunModel { + NO = 0, YES = 3 + }; + uint8_t useSunModel; + float domega; + float omega_0; //Rektaszension des Aufsteigenden Knotens plus Argument des Perigäums + float m_0; //coefficients for mean anomaly + float dm; //coefficients for mean anomaly + float e; //angle of earth's rotation axis + float e1; + float p1; //some parameter + float p2; //some parameter + } sunModelParameters; + + struct KalmanFilterParameters { + uint8_t activateKalmanFilter; + uint8_t requestResetFlag; + double maxToleratedTimeBetweenKalmanFilterExecutionSteps; + double processNoiseOmega[3]; + double processNoiseQuaternion[4]; + + double sensorNoiseSTR; + double sensorNoiseSS; + double sensorNoiseMAG; + double sensorNoiseRMU[3]; + + double sensorNoiseArwRmu; //Angular Random Walk + double sensorNoiseBsRMU; // Bias Stability + } kalmanFilterParameters; + + struct MagnetorquesParameter { + + double mtq0orientationMatrix[3][3]; + double mtq1orientationMatrix[3][3]; + double mtq2orientationMatrix[3][3]; + double alignmentMatrixMtq[3][3]; + double inverseAlignment[3][3]; + double DipolMax; // [Am^2] + + } magnetorquesParameter; + + struct DetumbleParameter { + + uint8_t detumblecounter; + double omegaDetumbleStart; + double omegaDetumbleEnd; + } detumbleParameter; +}; + +#endif /* ACSPARAMETERS_H_ */ -- 2.34.1 From 4583f0cb86fab232fd06d240eb6ad0fd36bb6fd1 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 19 Sep 2022 10:46:21 +0200 Subject: [PATCH 002/101] added Igrf13Model --- mission/controller/acs/Igrf13Model.cpp | 126 +++++++++++++++++++++++++ mission/controller/acs/Igrf13Model.h | 117 +++++++++++++++++++++++ 2 files changed, 243 insertions(+) create mode 100644 mission/controller/acs/Igrf13Model.cpp create mode 100644 mission/controller/acs/Igrf13Model.h diff --git a/mission/controller/acs/Igrf13Model.cpp b/mission/controller/acs/Igrf13Model.cpp new file mode 100644 index 00000000..de4659d8 --- /dev/null +++ b/mission/controller/acs/Igrf13Model.cpp @@ -0,0 +1,126 @@ +/* + * Igrf13Model.cpp + * + * Created on: 10 Mar 2022 + * Author: Robin Marquardt + */ + +#include "Igrf13Model.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace Math; + +Igrf13Model::Igrf13Model(){ +} +Igrf13Model::~Igrf13Model(){ +} + +void Igrf13Model::magFieldComp(const double longitude, const double gcLatitude, + const double altitude, timeval timeOfMagMeasurement, double* magFieldModelInertial) { + + double phi = longitude, theta = gcLatitude; //geocentric + /* Here is the co-latitude needed*/ + theta -= 90*PI/180; + theta *= (-1); + + double rE = 6371200.0; // radius earth [m] + /* Predefine recursive associated Legendre polynomials */ + double P11 = 1; + double P10 = P11; //P10 = P(n-1,m-0) + double dP11 = 0; //derivative + double dP10 = dP11; //derivative + + double P2 = 0, dP2 = 0, P20 = 0, dP20 = 0, K = 0; + + for (int m = 0; m <= igrfOrder; m++) { + for (int n = 1; n <= igrfOrder; n++) { + if (m <= n) { + /* Calculation of Legendre Polynoms (normalised) */ + if (n == m) { + P2 = sin(theta) * P11; + dP2 = sin(theta) * dP11 - cos(theta) * P11; + P11 = P2; + P10 = P11; + P20 = 0; + dP11 = dP2; + dP10 = dP11; + dP20 = 0; + } else if (n == 1) { + P2 = cos(theta) * P10; + dP2 = cos(theta) * dP10 - sin(theta) * P10; + P20 = P10; + P10 = P2; + dP20 = dP10; + dP10 = dP2; + } else { + K = (pow((n - 1), 2) - pow(m, 2)) + / ((2 * n - 1) * (2 * n - 3)); + P2 = cos(theta) * P10 - K * P20; + dP2 = cos(theta) * dP10 - sin(theta) * P10 - K * dP20; + P20 = P10; + P10 = P2; + dP20 = dP10; + dP10 = dP2; + } + /* gradient of scalar potential towards radius */ + magFieldModel[0]+=pow(rE/(altitude+rE),(n+2))*(n+1)* + ((updatedG[m][n-1]*cos(m*phi) + updatedH[m][n-1]*sin(m*phi))*P2); + /* gradient of scalar potential towards phi */ + magFieldModel[1]+=pow(rE/(altitude+rE),(n+2))* + ((updatedG[m][n-1]*cos(m*phi) + updatedH[m][n-1]*sin(m*phi))*dP2); + /* gradient of scalar potential towards theta */ + magFieldModel[2]+=pow(rE/(altitude+rE),(n+2))* + ((-updatedG[m][n-1]*sin(m*phi) + updatedH[m][n-1]*cos(m*phi))*P2*m); + } + } + } + + magFieldModel[1] *= -1; + magFieldModel[2] *= (-1 / sin(theta)); + + /* Next step: transform into inertial KOS (IJK)*/ + //Julean Centuries + double JD2000Floor = 0; + double JD2000 = MathOperations::convertUnixToJD2000(timeOfMagMeasurement); + JD2000Floor = floor(JD2000); + double JC2000 = JD2000Floor / 36525; + + double gst = 100.4606184 + 36000.77005361 * JC2000 + 0.00038793 * pow(JC2000,2) + - 0.000000026 * pow(JC2000,3); //greenwich sidereal time + gst *= PI/180; //convert to radians + double sec = (JD2000 - JD2000Floor) * 86400; // Seconds on this day (Universal time) // FROM GPS ? + double omega0 = 0.00007292115; // mean angular velocity earth [rad/s] + gst +=omega0 * sec; + + double lst = gst + longitude; //local sidereal time [rad] + + + + magFieldModelInertial[0] = magFieldModel[0] * cos(theta) + magFieldModel[1] * sin(theta)*cos(lst) - magFieldModel[1] * sin(lst); + magFieldModelInertial[1] = magFieldModel[0] * cos(theta) + magFieldModel[1] * sin(theta)*sin(lst) + magFieldModel[1] * cos(lst); + magFieldModelInertial[2] = magFieldModel[0] * sin(theta) + magFieldModel[1] * cos(lst); + + double normVecMagFieldInert[3] = {0,0,0}; + VectorOperations::normalize(magFieldModelInertial, normVecMagFieldInert, 3); +} + +void Igrf13Model::updateCoeffGH(timeval timeOfMagMeasurement){ + + double JD2000Igrf = (2458850.0-2451545); //Begin of IGRF-13 (2020-01-01,00:00:00) in JD2000 + double JD2000 = MathOperations::convertUnixToJD2000(timeOfMagMeasurement); + double days = ceil(JD2000-JD2000Igrf); + for(int i = 0;i <= igrfOrder; i++){ + for(int j = 0;j <= (igrfOrder-1); j++){ + updatedG[i][j] = coeffG[i][j] + svG[i][j] * (days/365); + updatedH[i][j] = coeffH[i][j] + svH[i][j] * (days/365); + } + } +} diff --git a/mission/controller/acs/Igrf13Model.h b/mission/controller/acs/Igrf13Model.h new file mode 100644 index 00000000..dadb9c4e --- /dev/null +++ b/mission/controller/acs/Igrf13Model.h @@ -0,0 +1,117 @@ +/* + * Igrf13Model.h + * + * Created on: 10 Mar 2022 + * Author: Robin Marquardt + * Description: Calculates the magnetic field vector of earth with the IGRF Model. + * Sources: https://www.ngdc.noaa.gov/IAGA/vmod/igrf.html + * https://doi.org/10.1186/s40623-020-01288-x + * J. Davis, Mathematical Modeling of Earth's Magnetic Field, TN, 2004 + * + * [Conversion of ENU (geocentric) to IJK: Skript Bahnmechanik für Raumfahrzeuge, + * Prof. Dr.-Ing. Stefanos Fasoulas / Dr.-Ing. Frank Zimmermann] + * + */ + +#ifndef IGRF13MODEL_H_ +#define IGRF13MODEL_H_ + +#include +#include +#include +#include + + +// Output should be transformed to [T] instead of [nT] +// Updating Coefficients has to be implemented yet. Question, updating everyday ? +class Igrf13Model { + +public: + Igrf13Model(); + virtual ~Igrf13Model(); + + // Main Function + void magFieldComp(const double longitude, const double gcLatitude, const double altitude, timeval timeOfMagMeasurement,double* magFieldModelInertial); + // Right now the radius for igrf is simply with r0 + altitude calculated. In reality the radius is oriented from the satellite to earth COM + // Difference up to 25 km, which is 5 % of the total flight altitude + /* Inputs: + * - longitude: geocentric longitude [rad] + * - latitude: geocentric latitude [rad] + * - altitude: [m] + * - timeOfMagMeasurement: time of actual measurement [s] + * + * Outputs: + * - magFieldModelInertial: Magnetic Field Vector in IJK KOS [nT]*/ + + + // Coefficient wary over year, could be updated sometimes. + void updateCoeffGH(timeval timeOfMagMeasurement); //Secular variation (SV) + double magFieldModel[3]; + +private: + const double coeffG[14][13] = {{-29404.8, -2499.6, 1363.2, 903.0, -234.3, 66.0, 80.6, 23.7, 5.0, -1.9, 3.0, -2.0, 0.1}, + {-1450.9, 2982.0, -2381.2, 809.5, 363.2, 65.5, -76.7, 9.7, 8.4, -6.2, -1.4, -0.1, -0.9}, + {0, 1677.0, 1236.2, 86.3, 187.8, 72.9, -8.2, -17.6, 2.9, -0.1, -2.5, 0.5, 0.5}, + {0, 0, 525.7, -309.4, -140.7, -121.5, 56.5, -0.5, -1.5, 1.7, 2.3, 1.3 ,0.7}, + {0 ,0 ,0, 48.0, -151.2, -36.2, 15.8, -21.1, -1.1, -0.9, -0.9, -1.2, -0.3}, + {0, 0, 0, 0, 13.5, 13.5, 6.4, 15.3, -13.2, 0.7, 0.3, 0.7, 0.8}, + {0, 0, 0, 0, 0,-64.7, -7.2, 13.7, 1.1, -0.9, -0.7, 0.3, 0.0}, + {0, 0, 0, 0, 0, 0, 9.8, -16.5, 8.8, 1.9, -0.1, 0.5, 0.8}, + {0, 0, 0, 0, 0, 0, 0, -0.3, -9.3, 1.4, 1.4, -0.3, 0.0}, + {0, 0, 0, 0, 0, 0, 0, 0, -11.9, -2.4, -0.6, -0.5, 0.4}, + {0, 0, 0, 0, 0, 0, 0, 0, 0, -3.8, 0.2, 0.1, 0.1}, + {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 3.1, -1.1, 0.5}, + {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, -0.3, -0.5}, + {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, -0.4}}; // [m][n] in nT + + const double coeffH[14][13] = {{0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}, + {4652.5, -2991.6, -82.1, 281.9, 47.7, -19.1, -51.5, 8.4, -23.4, 3.4, 0.0, -1.2, -0.9}, + {0, -734.6, 241.9, -158.4, 208.3, 25.1, -16.9, -15.3, 11.0, -0.2, 2.5, 0.5, 0.6}, + {0, 0, -543.4, 199.7, -121.2, 52.8, 2.2, 12.8, 9.8, 3.6, -0.6, 1.4, 1.4}, + {0, 0, 0, -349.7, 32.3, -64.5, 23.5, -11.7, -5.1, 4.8, -0.4, -1.8, -0.4}, + {0, 0, 0, 0, 98.9, 8.9, -2.2, 14.9, -6.3, -8.6, 0.6, 0.1, -1.3}, + {0, 0, 0, 0, 0, 68.1, -27.2, 3.6, 7.8, -0.1, -0.2, 0.8, -0.1}, + {0, 0, 0, 0, 0, 0, -1.8, -6.9, 0.4, -4.3, -1.7, -0.2, 0.3}, + {0, 0, 0, 0, 0, 0, 0, 2.8, -1.4, -3.4, -1.6, 0.6, -0.1}, + {0, 0, 0, 0, 0, 0, 0, 0, 9.6, -0.1, -3.0, 0.2, 0.5}, + {0, 0, 0, 0, 0, 0, 0, 0, 0, -8.8, -2.0, -0.9, 0.5}, + {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, -2.6, 0.0, -0.4}, + {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.5, -0.4}, + {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, -0.6}}; // [m][n] in nT + + const double svG[14][13] = {{5.7, -11, 2.2, -1.2, -0.3, -0.5, -0.1, 0, 0, 0, 0, 0 ,0}, + {7.4, -7, -5.9, -1.6, 0.5, -0.3, -0.2, 0.1, 0, 0, 0, 0,0}, + {0, -2.1, 3.1, -5.9, -0.6, 0.4, 0, -0.1, 0, 0, 0, 0, 0}, + {0, 0, -12, 5.2, 0.2, 1.3, 0.7, 0.4, 0, 0, 0, 0, 0}, + {0 ,0 ,0, -5.1, 1.3, -1.4, 0.1, -0.1, 0, 0, 0, 0, 0}, + {0, 0, 0, 0, 0.9, 0, -0.5, 0.4, 0, 0, 0, 0, 0}, + {0, 0, 0, 0, 0, 0.9, -0.8, 0.3, 0, 0, 0, 0, 0}, + {0, 0, 0, 0, 0, 0, 0.8, -0.1, 0, 0, 0, 0, 0}, + {0, 0, 0, 0, 0, 0, 0, 0.4, 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, 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}}; // [m][n] in nT + + const double svH[14][13] = {{0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}, + {-25.9, -30.2, 6, -0.1, 0, 0, 0.6, -0.2, 0, 0, 0, 0,0}, + {0, -22.4, -1.1, 6.5, 2.5, -1.6, 0.6, 0.6, 0, 0, 0, 0, 0}, + {0, 0, 0.5, 3.6, -0.6, -1.3, -0.8, -0.2, 0, 0, 0, 0, 0}, + {0 ,0 ,0, -5, 3, 0.8, -0.2, 0.5, 0, 0, 0, 0, 0}, + {0, 0, 0, 0, 0.3, 0, -1.1, -0.3, 0, 0, 0, 0, 0}, + {0, 0, 0, 0, 0, 1, 0.1, -0.4, 0, 0, 0, 0, 0}, + {0, 0, 0, 0, 0, 0, 0.3, 0.5, 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, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}}; // [m][n] in nT + + double updatedG[14][13]; + double updatedH[14][13]; + static const int igrfOrder = 13; // degree of truncation +}; + +#endif /* IGRF13MODEL_H_ */ -- 2.34.1 From b42986dd8a9c006f6430ea0428e6a765666011de Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 19 Sep 2022 11:10:28 +0200 Subject: [PATCH 003/101] added MathOperations to util folder --- mission/controller/acs/Igrf13Model.cpp | 2 +- mission/controller/acs/util/MathOperations.h | 297 +++++++++++++++++++ 2 files changed, 298 insertions(+), 1 deletion(-) create mode 100644 mission/controller/acs/util/MathOperations.h diff --git a/mission/controller/acs/Igrf13Model.cpp b/mission/controller/acs/Igrf13Model.cpp index de4659d8..fbdb481e 100644 --- a/mission/controller/acs/Igrf13Model.cpp +++ b/mission/controller/acs/Igrf13Model.cpp @@ -14,7 +14,7 @@ #include #include #include -#include +#include using namespace Math; diff --git a/mission/controller/acs/util/MathOperations.h b/mission/controller/acs/util/MathOperations.h new file mode 100644 index 00000000..57d9b7b4 --- /dev/null +++ b/mission/controller/acs/util/MathOperations.h @@ -0,0 +1,297 @@ +/* + * MathOperations.h + * + * Created on: 3 Mar 2022 + * Author: rooob + */ + +#ifndef MATH_MATHOPERATIONS_H_ +#define MATH_MATHOPERATIONS_H_ + +#include +#include +#include +#include +#include + +using namespace Math; + +template +class MathOperations { +public: + static void skewMatrix(const T1 vector[], T2 *result) { + // Input Dimension [3], Output [3][3] + result[0] = 0; + result[1] = -vector[2]; + result[2] = vector[1]; + result[3] = vector[2]; + result[4] = 0; + result[5] = -vector[0]; + result[6] = -vector[1]; + result[7] = vector[0]; + result[8] = 0; + } + static void vecTransposeVecMatrix(const T1 vector1[], const T1 transposeVector2[], + T2 *result, uint8_t size = 3) { + // Looks like MatrixOpertions::multiply is able to do the same thing + for (uint8_t resultColumn = 0; resultColumn < size; resultColumn++) { + for (uint8_t resultRow = 0; resultRow < size; resultRow++) { + result[resultColumn + size * resultRow] = vector1[resultRow] + * transposeVector2[resultColumn]; + + } + } + /*matrixSun[i][j] = sunEstB[i] * sunEstB[j]; + matrixMag[i][j] = magEstB[i] * magEstB[j]; + matrixSunMag[i][j] = sunEstB[i] * magEstB[j]; + matrixMagSun[i][j] = magEstB[i] * sunEstB[j];*/ + } + + static void selectionSort(const T1 *matrix, T1 *result, uint8_t rowSize, + uint8_t colSize) { + int min_idx; + T1 temp; + memcpy(result, matrix, rowSize * colSize * sizeof(*result)); + // One by one move boundary of unsorted subarray + for (int k = 0; k < rowSize; k++) { + for (int i = 0; i < colSize - 1; i++) { + // Find the minimum element in unsorted array + min_idx = i; + for (int j = i + 1; j < colSize; j++) { + if (result[j + k * colSize] + < result[min_idx + k * colSize]) { + min_idx = j; + } + } + // Swap the found minimum element with the first element + temp = result[i + k * colSize]; + result[i + k * colSize] = result[min_idx + k * colSize]; + result[min_idx + k * colSize] = temp; + } + } + } + + static void convertDateToJD2000(const T1 time, T2 julianDate){ + + // time = { Y, M, D, h, m,s} + // time in sec and microsec -> The Epoch (unixtime) + julianDate = 1721013.5 + 367*time[0]- floor(7/4*(time[0]+(time[1]+9)/12)) + +floor(275*time[1]/9)+time[2]+(60*time[3]+time[4]+(time(5)/60))/1440; + } + + static T1 convertUnixToJD2000(timeval time){ + //time = {{s},{us}} + T1 julianDate2000; + julianDate2000 = (time.tv_sec/86400.0)+2440587.5-2451545; + return julianDate2000; + } + + static void dcmFromQuat(const T1 vector[], T1 *outputDcm){ + // convention q = [qx,qy,qz, qw] + outputDcm[0] = pow(vector[0],2) - pow(vector[1],2) - pow(vector[2],2) + pow(vector[3],2); + outputDcm[1] = 2*(vector[0]*vector[1] + vector[2]*vector[3]); + outputDcm[2] = 2*(vector[0]*vector[2] - vector[1]*vector[3]); + + outputDcm[3] = 2*(vector[1]*vector[0] - vector[2]*vector[3]); + outputDcm[4] = -pow(vector[0],2) + pow(vector[1],2) - pow(vector[2],2) + pow(vector[3],2); + outputDcm[5] = 2*(vector[1]*vector[2] + vector[0]*vector[3]); + + outputDcm[6] = 2*(vector[2]*vector[0] + vector[1]*vector[3]); + outputDcm[7] = 2*(vector[2]*vector[1] - vector[0]*vector[3]); + outputDcm[8] = -pow(vector[0],2) - pow(vector[1],2) + pow(vector[2],2) + pow(vector[3],2); + + } + + static void cartesianFromLatLongAlt(const T1 lat, const T1 longi, const T1 alt, T2 *cartesianOutput){ + + double radiusPolar = 6378137; + double radiusEqua = 6356752.314; + + double eccentricity = sqrt(1 - pow(radiusPolar,2) / pow(radiusEqua,2)); + double auxRadius = radiusEqua / sqrt(1 - pow(eccentricity,2) * pow(sin(lat),2)); + + cartesianOutput[0] = (auxRadius + alt) * cos(lat) * cos(longi); + cartesianOutput[1] = (auxRadius + alt) * cos(lat) * sin(longi); + cartesianOutput[2] = ((1 - pow(eccentricity,2)) * auxRadius + alt) * sin(lat); + + } + + /* @brief: dcmEJ() - calculates the transformation matrix between ECEF and ECI frame + * @param: time Current time + * outputDcmEJ Transformation matrix from ECI (J) to ECEF (E) [3][3] + * @source: Fundamentals of Spacecraft Attitude Determination and Control, P.32ff + * Landis Markley and John L. Crassidis*/ + static void dcmEJ(timeval time, T1 * outputDcmEJ){ + + double JD2000Floor = 0; + double JD2000 = convertUnixToJD2000(time); + // Getting Julian Century from Day start : JD (Y,M,D,0,0,0) + JD2000Floor = floor(JD2000); + if ( ( JD2000 - JD2000Floor) < 0.5) { + JD2000Floor -= 0.5; + } + else { + JD2000Floor += 0.5; + } + + double JC2000 = JD2000Floor / 36525; + double sec = (JD2000 - JD2000Floor) * 86400; + double gmst = 0; //greenwich mean sidereal time + gmst = 24110.54841 + 8640184.812866 * JC2000 + 0.093104 * pow(JC2000,2) - + 0.0000062 * pow(JC2000,3) + 1.002737909350795 * sec; + double rest = gmst / 86400; + double FloorRest = floor(rest); + double secOfDay = rest-FloorRest; + secOfDay *= 86400; + gmst = secOfDay / 240 * PI / 180; + + outputDcmEJ[0] = cos(gmst); + outputDcmEJ[1] = sin(gmst); + outputDcmEJ[2] = 0; + outputDcmEJ[3] = -sin(gmst); + outputDcmEJ[4] = cos(gmst); + outputDcmEJ[5] = 0; + outputDcmEJ[6] = 0; + outputDcmEJ[7] = 0; + outputDcmEJ[8] = 1; + + } + + /* @brief: ecfToEciWithNutPre() - calculates the transformation matrix between ECEF and ECI frame + * give also the back the derivative of this matrix + * @param: unixTime Current time in Unix format + * outputDcmEJ Transformation matrix from ECI (J) to ECEF (E) [3][3] + * outputDotDcmEJ Derivative of transformation matrix [3][3] + * @source: Entwicklung einer Simulationsumgebung und robuster Algorithmen für das Lage- und + Orbitkontrollsystem der Kleinsatelliten Flying Laptop und PERSEUS, P.244ff + * Oliver Zeile + * https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_Studenten/Marquardt_Robin&openfile=896110*/ + static void ecfToEciWithNutPre(timeval unixTime, T1 * outputDcmEJ, T1 * outputDotDcmEJ ) { + +// TT = UTC/Unix + 32.184s (TAI Difference) + 27 (Leap Seconds in UTC since 1972) + 10 (initial Offset) +// International Atomic Time (TAI) + + double JD2000UTC1 = convertUnixToJD2000(unixTime); + +// Julian Date / century from TT + timeval terestrialTime = unixTime; + terestrialTime.tv_sec = unixTime.tv_sec + 32.184 + 37; + double JD2000TT = convertUnixToJD2000(terestrialTime); + double JC2000TT = JD2000TT / 36525; + +//------------------------------------------------------------------------------------- +// Calculation of Transformation from earth rotation Theta +//------------------------------------------------------------------------------------- + double theta[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; +// Earth Rotation angle + double era = 0; + era = 2* PI *(0.779057273264 + 1.00273781191135448 * JD2000UTC1); +// Greenwich Mean Sidereal Time + double gmst2000 = 0.014506 + 4612.15739966 * JC2000TT + 1.39667721 * pow(JC2000TT,2) - + 0.00009344 * pow(JC2000TT,3) + 0.00001882 * pow(JC2000TT,4); + double arcsecFactor = 1 * PI / (180 * 3600); + gmst2000 *= arcsecFactor; + gmst2000 += era; + + theta[0][0] = cos(gmst2000); + theta[0][1] = sin(gmst2000); + theta[0][2] = 0; + theta[1][0] = -sin(gmst2000); + theta[1][1] = cos(gmst2000); + theta[1][2] = 0; + theta[2][0] = 0; + theta[2][1] = 0; + theta[2][2] = 1; + +//------------------------------------------------------------------------------------- +// Calculation of Transformation from earth Precession P +//------------------------------------------------------------------------------------- + double precession[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; + + double zeta = 2306.2181 * JC2000TT + 0.30188 * pow(JC2000TT,2) + 0.017998 * pow(JC2000TT,3); + double theta2 = 2004.3109 * JC2000TT - 0.42665 * pow(JC2000TT,2) - 0.041833 * pow(JC2000TT,3); + double ze = zeta + 0.79280 * pow(JC2000TT,2) + 0.000205 * pow(JC2000TT,3); + + zeta *= arcsecFactor; + theta2 *= arcsecFactor; + ze *= arcsecFactor; + + precession[0][0]=-sin(ze)*sin(zeta)+cos(ze)*cos(theta2)*cos(zeta); + precession[1][0]=cos(ze)*sin(zeta)+sin(ze)*cos(theta2)*cos(zeta); + precession[2][0]=sin(theta2)*cos(zeta); + precession[0][1]=-sin(ze)*cos(zeta)-cos(ze)*cos(theta2)*sin(zeta); + precession[1][1]=cos(ze)*cos(zeta)-sin(ze)*cos(theta2)*sin(zeta); + precession[2][1]=-sin(theta2)*sin(zeta); + precession[0][2]=-cos(ze)*sin(theta2); + precession[1][2]=-sin(ze)*sin(theta2); + precession[2][2]=cos(theta2); + +//------------------------------------------------------------------------------------- +// Calculation of Transformation from earth Nutation N +//------------------------------------------------------------------------------------- + double nutation[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; +// lunar asc node + double Om = 125 * 3600 + 2 * 60 + 40.28 - (1934 * 3600 + 8 * 60 + 10.539) * JC2000TT + + 7.455 * pow(JC2000TT,2) + 0.008 * pow(JC2000TT,3); + Om *= arcsecFactor; +// delta psi approx + double dp = -17.2 * arcsecFactor *sin(Om); + +// delta eps approx + double de = 9.203 * arcsecFactor *cos(Om); + +// % true obliquity of the ecliptic eps p.71 (simplified) + double e = 23.43929111 * PI / 180 - 46.8150 / 3600 * JC2000TT * PI / 180;; + + nutation[0][0]=cos(dp); + nutation[1][0]=cos(e+de)*sin(dp); + nutation[2][0]=sin(e+de)*sin(dp); + nutation[0][1]=-cos(e)*sin(dp); + nutation[1][1]=cos(e)*cos(e+de)*cos(dp)+sin(e)*sin(e+de); + nutation[2][1]=cos(e)*sin(e+de)*cos(dp)-sin(e)*cos(e+de); + nutation[0][2]=-sin(e)*sin(dp); + nutation[1][2]=sin(e)*cos(e+de)*cos(dp)-cos(e)*sin(e+de); + nutation[2][2]=sin(e)*sin(e+de)*cos(dp)+cos(e)*cos(e+de); + +//------------------------------------------------------------------------------------- +// Calculation of Derivative of rotation matrix from earth +//------------------------------------------------------------------------------------- + double thetaDot[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; + double dotMatrix[3][3] = {{0,1,0},{-1,0,0},{0,0,0}}; + double omegaEarth = 0.000072921158553; + MatrixOperations::multiply(*dotMatrix, *theta, *thetaDot, 3, 3, 3); + MatrixOperations::multiplyScalar(*thetaDot, omegaEarth, *thetaDot, 3, 3); + +//------------------------------------------------------------------------------------- +// Calculation of transformation matrix and Derivative of transformation matrix +//------------------------------------------------------------------------------------- + double nutationPrecession[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; + MatrixOperations::multiply(*nutation, *precession, *nutationPrecession, 3, 3, 3); + MatrixOperations::multiply(*nutationPrecession, *theta, outputDcmEJ, 3, 3, 3); + + MatrixOperations::multiply(*nutationPrecession, *thetaDot, outputDotDcmEJ, 3, 3, 3); + + } + + static void inverseMatrixDimThree(const T1 *matrix, T1 * output){ + + int i,j; + double determinant; + double mat[3][3] = {{matrix[0], matrix[1], matrix[2]},{matrix[3], matrix[4], matrix[5]}, + {matrix[6], matrix[7], matrix[8]}}; + + for(i = 0; i < 3; i++) { + determinant = determinant + (mat[0][i] * (mat[1][(i+1)%3] * mat[2][(i+2)%3] - mat[1][(i+2)%3] * mat[2][(i+1)%3])); + } +// cout<<"\n\ndeterminant: "< Date: Mon, 19 Sep 2022 13:24:20 +0200 Subject: [PATCH 004/101] small fixes --- mission/controller/acs/AcsParameters.cpp | 4 +- mission/controller/acs/Igrf13Model.cpp | 7 +- mission/controller/acs/Igrf13Model.h | 119 ++++++++++--------- mission/controller/acs/util/MathOperations.h | 2 +- 4 files changed, 66 insertions(+), 66 deletions(-) diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index 91090028..a3c0211e 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -1,8 +1,8 @@ #include #include "AcsParameters.h" -#include -#include +//#include +#include AcsParameters::AcsParameters() { diff --git a/mission/controller/acs/Igrf13Model.cpp b/mission/controller/acs/Igrf13Model.cpp index fbdb481e..91bfad15 100644 --- a/mission/controller/acs/Igrf13Model.cpp +++ b/mission/controller/acs/Igrf13Model.cpp @@ -6,17 +6,16 @@ */ #include "Igrf13Model.h" -#include +#include #include #include -#include +//#include #include #include #include #include #include -using namespace Math; Igrf13Model::Igrf13Model(){ } @@ -28,7 +27,7 @@ void Igrf13Model::magFieldComp(const double longitude, const double gcLatitude, double phi = longitude, theta = gcLatitude; //geocentric /* Here is the co-latitude needed*/ - theta -= 90*PI/180; + theta -= 90*Math::PI/180; theta *= (-1); double rE = 6371200.0; // radius earth [m] diff --git a/mission/controller/acs/Igrf13Model.h b/mission/controller/acs/Igrf13Model.h index dadb9c4e..7e8d6e3f 100644 --- a/mission/controller/acs/Igrf13Model.h +++ b/mission/controller/acs/Igrf13Model.h @@ -16,15 +16,16 @@ #ifndef IGRF13MODEL_H_ #define IGRF13MODEL_H_ -#include +#include +//#include #include #include -#include +#include // Output should be transformed to [T] instead of [nT] // Updating Coefficients has to be implemented yet. Question, updating everyday ? -class Igrf13Model { +class Igrf13Model:public HasParametersIF{ public: Igrf13Model(); @@ -49,65 +50,65 @@ public: double magFieldModel[3]; private: - const double coeffG[14][13] = {{-29404.8, -2499.6, 1363.2, 903.0, -234.3, 66.0, 80.6, 23.7, 5.0, -1.9, 3.0, -2.0, 0.1}, - {-1450.9, 2982.0, -2381.2, 809.5, 363.2, 65.5, -76.7, 9.7, 8.4, -6.2, -1.4, -0.1, -0.9}, - {0, 1677.0, 1236.2, 86.3, 187.8, 72.9, -8.2, -17.6, 2.9, -0.1, -2.5, 0.5, 0.5}, - {0, 0, 525.7, -309.4, -140.7, -121.5, 56.5, -0.5, -1.5, 1.7, 2.3, 1.3 ,0.7}, - {0 ,0 ,0, 48.0, -151.2, -36.2, 15.8, -21.1, -1.1, -0.9, -0.9, -1.2, -0.3}, - {0, 0, 0, 0, 13.5, 13.5, 6.4, 15.3, -13.2, 0.7, 0.3, 0.7, 0.8}, - {0, 0, 0, 0, 0,-64.7, -7.2, 13.7, 1.1, -0.9, -0.7, 0.3, 0.0}, - {0, 0, 0, 0, 0, 0, 9.8, -16.5, 8.8, 1.9, -0.1, 0.5, 0.8}, - {0, 0, 0, 0, 0, 0, 0, -0.3, -9.3, 1.4, 1.4, -0.3, 0.0}, - {0, 0, 0, 0, 0, 0, 0, 0, -11.9, -2.4, -0.6, -0.5, 0.4}, - {0, 0, 0, 0, 0, 0, 0, 0, 0, -3.8, 0.2, 0.1, 0.1}, - {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 3.1, -1.1, 0.5}, - {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, -0.3, -0.5}, - {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, -0.4}}; // [m][n] in nT + const double coeffG[14][13] = {{-29404.8,-2499.6, 1363.2, 903.0,-234.3, 66.0, 80.6, 23.7, 5.0,-1.9, 3.0,-2.0, 0.1}, + { -1450.9, 2982.0,-2381.2, 809.5, 363.2, 65.5,-76.7, 9.7, 8.4,-6.2,-1.4,-0.1,-0.9}, + { 0 , 1677.0, 1236.2, 86.3, 187.8, 72.9, -8.2,-17.6, 2.9,-0.1,-2.5, 0.5, 0.5}, + { 0 , 0 , 525.7,-309.4,-140.7,-121.5, 56.5, -0.5, -1.5, 1.7, 2.3, 1.3, 0.7}, + { 0 , 0 , 0 , 48.0,-151.2, -36.2, 15.8,-21.1, -1.1,-0.9,-0.9,-1.2,-0.3}, + { 0 , 0 , 0 , 0 , 13.5, 13.5, 6.4, 15.3,-13.2, 0.7, 0.3, 0.7, 0.8}, + { 0 , 0 , 0 , 0 , 0 , -64.7, -7.2, 13.7, 1.1,-0.9,-0.7, 0.3, 0.0}, + { 0 , 0 , 0 , 0 , 0 , 0 , 9.8,-16.5, 8.8, 1.9,-0.1, 0.5, 0.8}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0 , -0.3, -9.3, 1.4, 1.4,-0.3, 0.0}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-11.9,-2.4,-0.6,-0.5, 0.4}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-3.8, 0.2, 0.1, 0.1}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 3.1,-1.1, 0.5}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-0.3,-0.5}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-0.4}}; // [m][n] in nT - const double coeffH[14][13] = {{0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}, - {4652.5, -2991.6, -82.1, 281.9, 47.7, -19.1, -51.5, 8.4, -23.4, 3.4, 0.0, -1.2, -0.9}, - {0, -734.6, 241.9, -158.4, 208.3, 25.1, -16.9, -15.3, 11.0, -0.2, 2.5, 0.5, 0.6}, - {0, 0, -543.4, 199.7, -121.2, 52.8, 2.2, 12.8, 9.8, 3.6, -0.6, 1.4, 1.4}, - {0, 0, 0, -349.7, 32.3, -64.5, 23.5, -11.7, -5.1, 4.8, -0.4, -1.8, -0.4}, - {0, 0, 0, 0, 98.9, 8.9, -2.2, 14.9, -6.3, -8.6, 0.6, 0.1, -1.3}, - {0, 0, 0, 0, 0, 68.1, -27.2, 3.6, 7.8, -0.1, -0.2, 0.8, -0.1}, - {0, 0, 0, 0, 0, 0, -1.8, -6.9, 0.4, -4.3, -1.7, -0.2, 0.3}, - {0, 0, 0, 0, 0, 0, 0, 2.8, -1.4, -3.4, -1.6, 0.6, -0.1}, - {0, 0, 0, 0, 0, 0, 0, 0, 9.6, -0.1, -3.0, 0.2, 0.5}, - {0, 0, 0, 0, 0, 0, 0, 0, 0, -8.8, -2.0, -0.9, 0.5}, - {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, -2.6, 0.0, -0.4}, - {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.5, -0.4}, - {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, -0.6}}; // [m][n] in nT + const double coeffH[14][13] = {{ 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 }, + {4652.5,-2991.6, -82.1, 281.9, 47.7,-19.1,-51.5, 8.4,-23.4, 3.4, 0.0,-1.2,-0.9}, + { 0 , -734.6, 241.9,-158.4, 208.3, 25.1,-16.9,-15.3, 11.0,-0.2, 2.5, 0.5, 0.6}, + { 0 , 0 ,-543.4, 199.7,-121.2, 52.8, 2.2, 12.8, 9.8, 3.6,-0.6, 1.4, 1.4}, + { 0 , 0 , 0 ,-349.7, 32.3,-64.5, 23.5,-11.7, -5.1, 4.8,-0.4,-1.8,-0.4}, + { 0 , 0 , 0 , 0 , 98.9, 8.9, -2.2, 14.9, -6.3,-8.6, 0.6, 0.1,-1.3}, + { 0 , 0 , 0 , 0 , 0 , 68.1,-27.2, 3.6, 7.8,-0.1,-0.2, 0.8,-0.1}, + { 0 , 0 , 0 , 0 , 0 , 0 , -1.8, -6.9, 0.4,-4.3,-1.7,-0.2, 0.3}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 2.8, -1.4,-3.4,-1.6, 0.6,-0.1}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 9.6,-0.1,-3.0, 0.2, 0.5}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-8.8,-2.0,-0.9, 0.5}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-2.6, 0.0,-0.4}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0.5,-0.4}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-0.6}}; // [m][n] in nT - const double svG[14][13] = {{5.7, -11, 2.2, -1.2, -0.3, -0.5, -0.1, 0, 0, 0, 0, 0 ,0}, - {7.4, -7, -5.9, -1.6, 0.5, -0.3, -0.2, 0.1, 0, 0, 0, 0,0}, - {0, -2.1, 3.1, -5.9, -0.6, 0.4, 0, -0.1, 0, 0, 0, 0, 0}, - {0, 0, -12, 5.2, 0.2, 1.3, 0.7, 0.4, 0, 0, 0, 0, 0}, - {0 ,0 ,0, -5.1, 1.3, -1.4, 0.1, -0.1, 0, 0, 0, 0, 0}, - {0, 0, 0, 0, 0.9, 0, -0.5, 0.4, 0, 0, 0, 0, 0}, - {0, 0, 0, 0, 0, 0.9, -0.8, 0.3, 0, 0, 0, 0, 0}, - {0, 0, 0, 0, 0, 0, 0.8, -0.1, 0, 0, 0, 0, 0}, - {0, 0, 0, 0, 0, 0, 0, 0.4, 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, 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}}; // [m][n] in nT + const double svG[14][13] = {{5.7,-11.0, 2.2,-1.2,-0.3,-0.5,-0.1, 0 , 0, 0, 0, 0 ,0}, + {7.4, -7.0, -5.9,-1.6, 0.5,-0.3,-0.2, 0.1, 0, 0, 0, 0, 0}, + {0 , -2.1, 3.1,-5.9,-0.6, 0.4, 0.0,-0.1, 0, 0, 0, 0, 0}, + {0 , 0 ,-12.0, 5.2, 0.2, 1.3, 0.7, 0.4, 0, 0, 0, 0, 0}, + {0 , 0 , 0 ,-5.1, 1.3,-1.4, 0.1,-0.1, 0, 0, 0, 0, 0}, + {0 , 0 , 0 , 0 , 0.9, 0.0,-0.5, 0.4, 0, 0, 0, 0, 0}, + {0 , 0 , 0 , 0 , 0 , 0.9,-0.8, 0.3, 0, 0, 0, 0, 0}, + {0 , 0 , 0 , 0 , 0 , 0 , 0.8,-0.1, 0, 0, 0, 0, 0}, + {0 , 0 , 0 , 0 , 0 , 0 , 0 , 0.4, 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 , 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}}; // [m][n] in nT - const double svH[14][13] = {{0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}, - {-25.9, -30.2, 6, -0.1, 0, 0, 0.6, -0.2, 0, 0, 0, 0,0}, - {0, -22.4, -1.1, 6.5, 2.5, -1.6, 0.6, 0.6, 0, 0, 0, 0, 0}, - {0, 0, 0.5, 3.6, -0.6, -1.3, -0.8, -0.2, 0, 0, 0, 0, 0}, - {0 ,0 ,0, -5, 3, 0.8, -0.2, 0.5, 0, 0, 0, 0, 0}, - {0, 0, 0, 0, 0.3, 0, -1.1, -0.3, 0, 0, 0, 0, 0}, - {0, 0, 0, 0, 0, 1, 0.1, -0.4, 0, 0, 0, 0, 0}, - {0, 0, 0, 0, 0, 0, 0.3, 0.5, 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, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}}; // [m][n] in nT + const double svH[14][13] = {{ 0.0, 0.0, 0 , 0.0, 0.0, 0.0, 0.0, 0.0, 0, 0, 0, 0, 0}, + {-25.9,-30.2, 6.0,-0.1, 0.0, 0.0, 0.6,-0.2, 0, 0, 0, 0, 0}, + { 0 ,-22.4,-1.1, 6.5, 2.5,-1.6, 0.6, 0.6, 0, 0, 0, 0, 0}, + { 0 , 0 , 0.5, 3.6,-0.6,-1.3,-0.8,-0.2, 0, 0, 0, 0, 0}, + { 0 , 0 , 0 ,-5.0, 3.0, 0.8,-0.2, 0.5, 0, 0, 0, 0, 0}, + { 0 , 0 , 0 , 0 , 0.3, 0.0,-1.1,-0.3, 0, 0, 0, 0, 0}, + { 0 , 0 , 0 , 0 , 0 , 1.0, 0.1,-0.4, 0, 0, 0, 0, 0}, + { 0 , 0 , 0 , 0 , 0 , 0 , 0.3, 0.5, 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 , 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 , 0 , 0 , 0 , 0 , 0 , 0 , 0, 0, 0, 0, 0}}; // [m][n] in nT double updatedG[14][13]; double updatedH[14][13]; diff --git a/mission/controller/acs/util/MathOperations.h b/mission/controller/acs/util/MathOperations.h index 57d9b7b4..82d19b19 100644 --- a/mission/controller/acs/util/MathOperations.h +++ b/mission/controller/acs/util/MathOperations.h @@ -8,7 +8,7 @@ #ifndef MATH_MATHOPERATIONS_H_ #define MATH_MATHOPERATIONS_H_ -#include +#include #include #include #include -- 2.34.1 From 8b6d3c98358d896c15d207e9a95f2b717116544b Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 19 Sep 2022 14:09:14 +0200 Subject: [PATCH 005/101] small formating-fixes --- mission/controller/acs/AcsParameters.cpp | 22 ++--- mission/controller/acs/Igrf13Model.h | 106 +++++++++++------------ 2 files changed, 64 insertions(+), 64 deletions(-) diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index a3c0211e..63d8951d 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -8,9 +8,9 @@ AcsParameters::AcsParameters() { onBoardParams.sampleTime = 0.1; - inertiaEIVE.inertiaMatrix = {{ 1, 0, 0}, - { 0, 1, 0}, - { 0,0.5, 1}}; + inertiaEIVE.inertiaMatrix = {{ 1.0, 0.0, 0.0}, + { 0.0, 1.0, 0.0}, + { 0.0, 0.5, 1.0}}; mgmHandlingParameters.mgm0orientationMatrix = {{ 0, 0,-1}, { 0, 1, 0}, @@ -32,16 +32,16 @@ AcsParameters::AcsParameters() { rwHandlingParameters.maxTrq = 0.0032; //3.2 [mNm] //Geometry frame - rwMatrices.alignmentMatrix = {{ 0.9205, 0,-0.9205, 0}, - { 0,-0.9205, 0, 0.9205}, - { 0.3907, 0.3907, 0.3907, 0.3907}}; + rwMatrices.alignmentMatrix = {{ 0.9205, 0.0000, -0.9205, 0.0000}, + { 0.0000, -0.9205, 0.0000, 0.9205}, + { 0.3907, 0.3907, 0.3907, 0.3907}}; - rwMatrices.pseudoInverse = {{ 0.4434,-0.2845, 0.3597}, - { 0.2136,-0.3317, 1.0123}, - {-0.8672,-0.1406, 0.1778}, - { 0.6426, 0.4794, 1.3603}}; + rwMatrices.pseudoInverse = {{ 0.4434, -0.2845, 0.3597}, + { 0.2136, -0.3317, 1.0123}, + { -0.8672, -0.1406, 0.1778}, + { 0.6426, 0.4794, 1.3603}}; - rwMatrices.nullspace = {-0.7358, 0.5469,-0.3637,-0.1649}; + rwMatrices.nullspace = { -0.7358, 0.5469, -0.3637, -0.1649}; kalmanFilterParameters.sensorNoiseSS = 8 * Math::PI / 180; kalmanFilterParameters.sensorNoiseMAG = 4 * Math::PI / 180; diff --git a/mission/controller/acs/Igrf13Model.h b/mission/controller/acs/Igrf13Model.h index 7e8d6e3f..6e46a90e 100644 --- a/mission/controller/acs/Igrf13Model.h +++ b/mission/controller/acs/Igrf13Model.h @@ -52,63 +52,63 @@ public: private: const double coeffG[14][13] = {{-29404.8,-2499.6, 1363.2, 903.0,-234.3, 66.0, 80.6, 23.7, 5.0,-1.9, 3.0,-2.0, 0.1}, { -1450.9, 2982.0,-2381.2, 809.5, 363.2, 65.5,-76.7, 9.7, 8.4,-6.2,-1.4,-0.1,-0.9}, - { 0 , 1677.0, 1236.2, 86.3, 187.8, 72.9, -8.2,-17.6, 2.9,-0.1,-2.5, 0.5, 0.5}, - { 0 , 0 , 525.7,-309.4,-140.7,-121.5, 56.5, -0.5, -1.5, 1.7, 2.3, 1.3, 0.7}, - { 0 , 0 , 0 , 48.0,-151.2, -36.2, 15.8,-21.1, -1.1,-0.9,-0.9,-1.2,-0.3}, - { 0 , 0 , 0 , 0 , 13.5, 13.5, 6.4, 15.3,-13.2, 0.7, 0.3, 0.7, 0.8}, - { 0 , 0 , 0 , 0 , 0 , -64.7, -7.2, 13.7, 1.1,-0.9,-0.7, 0.3, 0.0}, - { 0 , 0 , 0 , 0 , 0 , 0 , 9.8,-16.5, 8.8, 1.9,-0.1, 0.5, 0.8}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0 , -0.3, -9.3, 1.4, 1.4,-0.3, 0.0}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-11.9,-2.4,-0.6,-0.5, 0.4}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-3.8, 0.2, 0.1, 0.1}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 3.1,-1.1, 0.5}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-0.3,-0.5}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-0.4}}; // [m][n] in nT + { 0.0, 1677.0, 1236.2, 86.3, 187.8, 72.9, -8.2,-17.6, 2.9,-0.1,-2.5, 0.5, 0.5}, + { 0.0, 0.0, 525.7,-309.4,-140.7,-121.5, 56.5, -0.5, -1.5, 1.7, 2.3, 1.3, 0.7}, + { 0.0, 0.0, 0.0, 48.0,-151.2, -36.2, 15.8,-21.1, -1.1,-0.9,-0.9,-1.2,-0.3}, + { 0.0, 0.0, 0.0, 0.0, 13.5, 13.5, 6.4, 15.3,-13.2, 0.7, 0.3, 0.7, 0.8}, + { 0.0, 0.0, 0.0, 0.0, 0.0, -64.7, -7.2, 13.7, 1.1,-0.9,-0.7, 0.3, 0.0}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.8,-16.5, 8.8, 1.9,-0.1, 0.5, 0.8}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3, -9.3, 1.4, 1.4,-0.3, 0.0}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,-11.9,-2.4,-0.6,-0.5, 0.4}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,-3.8, 0.2, 0.1, 0.1}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.1,-1.1, 0.5}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,-0.3,-0.5}, + { 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.4}}; // [m][n] in nT - const double coeffH[14][13] = {{ 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 }, + const double coeffH[14][13] = {{ 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 }, {4652.5,-2991.6, -82.1, 281.9, 47.7,-19.1,-51.5, 8.4,-23.4, 3.4, 0.0,-1.2,-0.9}, - { 0 , -734.6, 241.9,-158.4, 208.3, 25.1,-16.9,-15.3, 11.0,-0.2, 2.5, 0.5, 0.6}, - { 0 , 0 ,-543.4, 199.7,-121.2, 52.8, 2.2, 12.8, 9.8, 3.6,-0.6, 1.4, 1.4}, - { 0 , 0 , 0 ,-349.7, 32.3,-64.5, 23.5,-11.7, -5.1, 4.8,-0.4,-1.8,-0.4}, - { 0 , 0 , 0 , 0 , 98.9, 8.9, -2.2, 14.9, -6.3,-8.6, 0.6, 0.1,-1.3}, - { 0 , 0 , 0 , 0 , 0 , 68.1,-27.2, 3.6, 7.8,-0.1,-0.2, 0.8,-0.1}, - { 0 , 0 , 0 , 0 , 0 , 0 , -1.8, -6.9, 0.4,-4.3,-1.7,-0.2, 0.3}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 2.8, -1.4,-3.4,-1.6, 0.6,-0.1}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 9.6,-0.1,-3.0, 0.2, 0.5}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-8.8,-2.0,-0.9, 0.5}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-2.6, 0.0,-0.4}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0.5,-0.4}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 , 0 ,-0.6}}; // [m][n] in nT + { 0.0, -734.6, 241.9,-158.4, 208.3, 25.1,-16.9,-15.3, 11.0,-0.2, 2.5, 0.5, 0.6}, + { 0.0, 0.0,-543.4, 199.7,-121.2, 52.8, 2.2, 12.8, 9.8, 3.6,-0.6, 1.4, 1.4}, + { 0.0, 0.0, 0.0,-349.7, 32.3,-64.5, 23.5,-11.7, -5.1, 4.8,-0.4,-1.8,-0.4}, + { 0.0, 0.0, 0.0, 0.0, 98.9, 8.9, -2.2, 14.9, -6.3,-8.6, 0.6, 0.1,-1.3}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 68.1,-27.2, 3.6, 7.8,-0.1,-0.2, 0.8,-0.1}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8, -6.9, 0.4,-4.3,-1.7,-0.2, 0.3}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8, -1.4,-3.4,-1.6, 0.6,-0.1}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.6,-0.1,-3.0, 0.2, 0.5}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,-8.8,-2.0,-0.9, 0.5}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,-2.6, 0.0,-0.4}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5,-0.4}, + { 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.6}}; // [m][n] in nT - const double svG[14][13] = {{5.7,-11.0, 2.2,-1.2,-0.3,-0.5,-0.1, 0 , 0, 0, 0, 0 ,0}, - {7.4, -7.0, -5.9,-1.6, 0.5,-0.3,-0.2, 0.1, 0, 0, 0, 0, 0}, - {0 , -2.1, 3.1,-5.9,-0.6, 0.4, 0.0,-0.1, 0, 0, 0, 0, 0}, - {0 , 0 ,-12.0, 5.2, 0.2, 1.3, 0.7, 0.4, 0, 0, 0, 0, 0}, - {0 , 0 , 0 ,-5.1, 1.3,-1.4, 0.1,-0.1, 0, 0, 0, 0, 0}, - {0 , 0 , 0 , 0 , 0.9, 0.0,-0.5, 0.4, 0, 0, 0, 0, 0}, - {0 , 0 , 0 , 0 , 0 , 0.9,-0.8, 0.3, 0, 0, 0, 0, 0}, - {0 , 0 , 0 , 0 , 0 , 0 , 0.8,-0.1, 0, 0, 0, 0, 0}, - {0 , 0 , 0 , 0 , 0 , 0 , 0 , 0.4, 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 , 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}}; // [m][n] in nT + const double svG[14][13] = {{5.7,-11.0, 2.2,-1.2,-0.3,-0.5,-0.1, 0.0, 0.0, 0.0, 0.0, 0.0 ,0.0}, + {7.4, -7.0, -5.9,-1.6, 0.5,-0.3,-0.2, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, -2.1, 3.1,-5.9,-0.6, 0.4, 0.0,-0.1, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0,-12.0, 5.2, 0.2, 1.3, 0.7, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0,-5.1, 1.3,-1.4, 0.1,-0.1, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.9, 0.0,-0.5, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.9,-0.8, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.8,-0.1, 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.4, 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}, + {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, 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, 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}}; // [m][n] in nT - const double svH[14][13] = {{ 0.0, 0.0, 0 , 0.0, 0.0, 0.0, 0.0, 0.0, 0, 0, 0, 0, 0}, - {-25.9,-30.2, 6.0,-0.1, 0.0, 0.0, 0.6,-0.2, 0, 0, 0, 0, 0}, - { 0 ,-22.4,-1.1, 6.5, 2.5,-1.6, 0.6, 0.6, 0, 0, 0, 0, 0}, - { 0 , 0 , 0.5, 3.6,-0.6,-1.3,-0.8,-0.2, 0, 0, 0, 0, 0}, - { 0 , 0 , 0 ,-5.0, 3.0, 0.8,-0.2, 0.5, 0, 0, 0, 0, 0}, - { 0 , 0 , 0 , 0 , 0.3, 0.0,-1.1,-0.3, 0, 0, 0, 0, 0}, - { 0 , 0 , 0 , 0 , 0 , 1.0, 0.1,-0.4, 0, 0, 0, 0, 0}, - { 0 , 0 , 0 , 0 , 0 , 0 , 0.3, 0.5, 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 , 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 , 0 , 0 , 0 , 0 , 0 , 0 , 0, 0, 0, 0, 0}}; // [m][n] in nT + const double svH[14][13] = {{ 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}, + {-25.9,-30.2, 6.0,-0.1, 0.0, 0.0, 0.6,-0.2, 0.0, 0.0, 0.0, 0.0, 0.0}, + { 0.0,-22.4,-1.1, 6.5, 2.5,-1.6, 0.6, 0.6, 0.0, 0.0, 0.0, 0.0, 0.0}, + { 0.0, 0.0, 0.5, 3.6,-0.6,-1.3,-0.8,-0.2, 0.0, 0.0, 0.0, 0.0, 0.0}, + { 0.0, 0.0, 0.0,-5.0, 3.0, 0.8,-0.2, 0.5, 0.0, 0.0, 0.0, 0.0, 0.0}, + { 0.0, 0.0, 0.0, 0.0, 0.3, 0.0,-1.1,-0.3, 0.0, 0.0, 0.0, 0.0, 0.0}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.1,-0.4, 0.0, 0.0, 0.0, 0.0, 0.0}, + { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.5, 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}, + { 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, 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, 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, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}}; // [m][n] in nT double updatedG[14][13]; double updatedH[14][13]; -- 2.34.1 From d497dd53c5b2c4dddd3df2017298e884a3dbe43d Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 19 Sep 2022 14:28:54 +0200 Subject: [PATCH 006/101] added MKF --- .../acs/MultiplicativeKalmanFilter.cpp | 1205 +++++++++++++++++ .../acs/MultiplicativeKalmanFilter.h | 107 ++ 2 files changed, 1312 insertions(+) create mode 100644 mission/controller/acs/MultiplicativeKalmanFilter.cpp create mode 100644 mission/controller/acs/MultiplicativeKalmanFilter.h diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.cpp b/mission/controller/acs/MultiplicativeKalmanFilter.cpp new file mode 100644 index 00000000..5d895566 --- /dev/null +++ b/mission/controller/acs/MultiplicativeKalmanFilter.cpp @@ -0,0 +1,1205 @@ +/* + * MultiplicativeKalmanFilter.cpp + * + * Created on: 4 Feb 2022 + * Author: rooob + */ + +#include +#include +#include +#include +#include +#include +#include "MultiplicativeKalmanFilter.h" +#include +#include + +/*Initialisation of values for parameters in constructor*/ +MultiplicativeKalmanFilter::MultiplicativeKalmanFilter(AcsParameters *acsParameters_) : + initialQuaternion { 0.5, 0.5, 0.5, 0.5 },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() { + +} + +void MultiplicativeKalmanFilter::loadAcsParameters( + AcsParameters *acsParameters_) { + inertiaEIVE = &(acsParameters_->inertiaEIVE); + kalmanFilterParameters = &(acsParameters_->kalmanFilterParameters); /*Sensor noises also here*/ +} + +void MultiplicativeKalmanFilter::reset() { + +} + +void 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) { // valids for "model measurements"? + // check for valid mag/sun + if (*validMagField_ && *validSS && *validSSModel && *validMagModel) { + validInit = true; + //AcsParameters mekfEstParams; + //loadAcsParameters(&mekfEstParams); + // QUEST ALGO ----------------------------------------------------------------------- + double sigmaSun = 0, sigmaMag = 0, sigmaGyro = 0; + sigmaSun = kalmanFilterParameters->sensorNoiseSS; + sigmaMag = kalmanFilterParameters->sensorNoiseMAG; + + sigmaGyro = 0.1*3.141/180; // acs parameters + + double normMagB[3] = {0,0,0}, normSunB[3] = {0,0,0}, + normMagJ[3] = {0,0,0}, normSunJ[3] = {0,0,0}; + VectorOperations::normalize(magneticField_, normMagB, 3); // b2 + VectorOperations::normalize(sunDir_, normSunB, 3); //b1 + VectorOperations::normalize(magFieldJ, normMagJ, 3); //r2 + VectorOperations::normalize(sunDirJ, normSunJ, 3); //r1 + + double thirdAxis_B[3] = {0,0,0}, thirdAxis_J[3] = {0,0,0}; + VectorOperations::cross(normSunJ, normMagJ, thirdAxis_J); + VectorOperations::cross(normSunB, normMagB, thirdAxis_B); + VectorOperations::normalize(thirdAxis_J, thirdAxis_J, 3); //rx + VectorOperations::normalize(thirdAxis_B, thirdAxis_B, 3); //bx + + double weigthSun= 1 / (sigmaSun * sigmaSun); //a1 + double weigthMag= 1 / (sigmaMag * sigmaMag); //a2 + + double a[3] = {0,0,0}, b[3] = {0,0,0}; + VectorOperations::mulScalar(normSunB, weigthSun, a, 3); //a + VectorOperations::mulScalar(normMagB, weigthMag, b, 3); //b + + double thirdAxisCross[3] = {0,0,0}, weightACross[3] = {0,0,0}, + weightBCross[3] = {0,0,0},weigthCrossSum[3] = {0,0,0}; + VectorOperations::cross(thirdAxis_B, thirdAxis_J, + thirdAxisCross); //cross(bx,rx) + VectorOperations::cross(a, normSunJ, weightACross); + VectorOperations::cross(b, normMagJ, weightBCross); + VectorOperations::add(weightACross, weightBCross, + weigthCrossSum); + + double thirdAxisSum[3] = {0,0,0}, sum2[3] = {0,0,0}; + VectorOperations::add(thirdAxis_B, thirdAxis_J, thirdAxisSum); + VectorOperations::add(weightACross, weightBCross, sum2); + + double alpha = 0, beta = 0, gamma = 0, constPlus = 0, constMin = 0; + alpha = (1 + VectorOperations::dot(thirdAxis_B, thirdAxis_J)) + * (VectorOperations::dot(a, normSunJ) + + VectorOperations::dot(b, normMagJ)) + + VectorOperations::dot(thirdAxisCross, weigthCrossSum); + beta = VectorOperations::dot(thirdAxisSum, sum2); + gamma = sqrt(alpha * alpha + beta * beta); + constPlus = 1 + / (2 + * sqrt( + gamma * (gamma + alpha) + * (1 + + VectorOperations::dot( + thirdAxis_B, + thirdAxis_J)))); + constMin = 1 + / (2 + * sqrt( + gamma * (gamma - alpha) + * (1 + + VectorOperations::dot( + thirdAxis_B, + thirdAxis_J)))); + + /*Quaternion Computation*/ + double quat[3] = {0,0,0}, var1[3] = {0,0,0}, var2[3] = {0,0,0}; + if (alpha >= 0) { + VectorOperations::mulScalar(thirdAxisCross, gamma + alpha, + var1, 3); + VectorOperations::add(thirdAxis_B, thirdAxis_J, var2, 3); + VectorOperations::mulScalar(var2, beta, var2, 3); + VectorOperations::add(var1, var2, quat); + + for (int i = 0; i < 3; i++) { + initialQuaternion[i] = quat[i]; + } + initialQuaternion[3] = (gamma + alpha) + * (1 + + VectorOperations::dot(thirdAxis_B, + thirdAxis_J)); + VectorOperations::mulScalar(initialQuaternion, + constPlus, initialQuaternion, 4); + } else { + double diffGammaAlpha = gamma - alpha; + VectorOperations::mulScalar(thirdAxisCross, beta, var1, 3); + VectorOperations::add(thirdAxis_B, thirdAxis_J, var2, 3); + VectorOperations::mulScalar(var2, diffGammaAlpha, var2, 3); + VectorOperations::add(var1, var2, quat); + for (int i = 0; i < 3; i++) { + initialQuaternion[i] = quat[i]; + } + initialQuaternion[3] = beta + * (1 + + VectorOperations::dot(thirdAxis_B, + thirdAxis_J)); + VectorOperations::mulScalar(initialQuaternion, + constMin, initialQuaternion, 4); + + } + propagatedQuaternion[0] = initialQuaternion[0]; + propagatedQuaternion[1] = initialQuaternion[1]; + propagatedQuaternion[2] = initialQuaternion[2]; + propagatedQuaternion[3] = initialQuaternion[3]; + + /*Initial Covariance Matrix------------------------------------ */ + double dcmBJ[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, + sunEstB[3] = {0,0,0}, magEstB[3] = {0,0,0}; + QuaternionOperations::toDcm(initialQuaternion, dcmBJ); + MatrixOperations::multiply(*dcmBJ, normSunJ, sunEstB, 3, 3, 1); + MatrixOperations::multiply(*dcmBJ, normMagJ, magEstB, 3, 3, + 1); + + double matrixSun[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, + matrixMag[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, + matrixSunMag[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, + matrixMagSun[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; + /* vector*transpose(vector)*/ + MatrixOperations::multiply(sunEstB, sunEstB, *matrixSun, 3, 1, 3); + MatrixOperations::multiply(magEstB, magEstB, *matrixMag, 3, 1, 3); + MatrixOperations::multiply(sunEstB, magEstB, *matrixSunMag, 3, 1, 3); + MatrixOperations::multiply(magEstB, sunEstB, *matrixMagSun, 3, 1, 3); + + double partA[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, partB = 0; + MatrixOperations::multiplyScalar(*matrixSun, + weigthSun * weigthSun, *matrixSun, 3, 3); + MatrixOperations::multiplyScalar(*matrixMag, + weigthMag * weigthMag, *matrixMag, 3, 3); + MatrixOperations::add(*matrixSunMag, *matrixMagSun, *partA, 3, + 3); + double factor = weigthMag * weigthSun + * VectorOperations::dot(sunEstB, magEstB); + MatrixOperations::multiplyScalar(*partA, factor, *partA, 3, 3); + MatrixOperations::add(*partA, *matrixSun, *partA, 3, 3); + MatrixOperations::add(*partA, *matrixMag, *partA, 3, 3); + + double crossSunMag[3] = {0,0,0}; + double identityMatrix3[3][3] = { { 1, 0, 0 }, { 0, 1, 0 }, { 0, 0, 1 } }; + VectorOperations::cross(sunEstB, magEstB, crossSunMag); + partB = + 1 + / (weigthMag * weigthSun + * pow( + VectorOperations::norm( + crossSunMag, 3), 2)); + MatrixOperations::multiplyScalar(*partA, partB, *partA, 3, 3); + MatrixOperations::add(*matrixSunMag, *identityMatrix3, *partA, 3, + 3); + factor = 1 / (weigthMag + weigthMag); + + double questCovMatrix[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; + MatrixOperations::multiplyScalar(*partA, factor, + *questCovMatrix, 3, 3); + double initGyroCov[3][3] = {{pow(sigmaGyro,2),0,0},{0,pow(sigmaGyro,2),0}, + {0,0,pow(sigmaGyro,2)}}; + initialCovarianceMatrix[0][0] = questCovMatrix[0][0]; + initialCovarianceMatrix[0][1] = questCovMatrix[0][1]; + initialCovarianceMatrix[0][2] = questCovMatrix[0][2]; + initialCovarianceMatrix[0][3] = 0; + initialCovarianceMatrix[0][4] = 0; + initialCovarianceMatrix[0][5] = 0; + initialCovarianceMatrix[1][0] = questCovMatrix[1][0]; + initialCovarianceMatrix[1][1] = questCovMatrix[1][1]; + initialCovarianceMatrix[1][2] = questCovMatrix[1][2]; + initialCovarianceMatrix[1][3] = 0; + initialCovarianceMatrix[1][4] = 0; + initialCovarianceMatrix[1][5] = 0; + initialCovarianceMatrix[2][0] = questCovMatrix[2][0]; + initialCovarianceMatrix[2][1] = questCovMatrix[2][1]; + initialCovarianceMatrix[2][2] = questCovMatrix[2][2]; + initialCovarianceMatrix[2][3] = 0; + initialCovarianceMatrix[2][4] = 0; + initialCovarianceMatrix[2][5] = 0; + initialCovarianceMatrix[3][0] = 0; + initialCovarianceMatrix[3][1] = 0; + initialCovarianceMatrix[3][2] = 0; + initialCovarianceMatrix[3][3] = initGyroCov[0][0]; + initialCovarianceMatrix[3][4] = initGyroCov[0][1]; + initialCovarianceMatrix[3][5] = initGyroCov[0][2]; + initialCovarianceMatrix[4][0] = 0; + initialCovarianceMatrix[4][1] = 0; + initialCovarianceMatrix[4][2] = 0; + initialCovarianceMatrix[4][3] = initGyroCov[1][0]; + initialCovarianceMatrix[4][4] = initGyroCov[1][1]; + initialCovarianceMatrix[4][5] = initGyroCov[1][2]; + initialCovarianceMatrix[5][0] = 0; + initialCovarianceMatrix[5][1] = 0; + initialCovarianceMatrix[5][2] = 0; + initialCovarianceMatrix[5][3] = initGyroCov[2][0]; + initialCovarianceMatrix[5][4] = initGyroCov[2][1]; + initialCovarianceMatrix[5][5] = initGyroCov[2][2]; + //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}}; + } else { + // no initialisation possible, no valid measurements + validInit = false; + } +} + +// --------------- MEKF DISCRETE TIME STEP ------------------------------- +ReturnValue_t MultiplicativeKalmanFilter::mekfEst( + const double *quaternionSTR, const bool *validSTR_, + const double *rateRMUs_, const bool *validRMUs_, + 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 *outputQuat, double *outputSatRate) { + + // Check for RMU Measurements + //AcsParameters mekfEstParams; + //loadAcsParameters(&mekfEstParams); + int MDF = 0; // Matrix Dimension Factor + if (!(*validRMUs_)){ + validMekf = false; + return KALMAN_NO_RMU_MEAS; + } + // Check for Model Calculations + else if (!(*validSSModel) || !(*validMagModel)){ + validMekf = false; + return KALMAN_NO_MODEL; + } + // Check Measurements available from SS, MAG, STR + if (*validSS && *validMagField_ && *validSTR_){ + sensorsAvail = 1; + MDF = 9; + } + else if (*validSS && *validMagField_ && !(*validSTR_)){ + sensorsAvail = 2; + MDF = 6; + } + else if (*validSS && !(*validMagField_) && *validSTR_){ + sensorsAvail = 3; + MDF = 6; + } + else if (!(*validSS) && *validMagField_ && *validSTR_){ + sensorsAvail = 4; + MDF = 6; + } + else if (*validSS && !(*validMagField_) && !(*validSTR_)){ + sensorsAvail = 5; + MDF = 3; + } + else if (!(*validSS) && *validMagField_ && !(*validSTR_)){ + sensorsAvail = 6; + MDF = 3; + } + else if (!(*validSS) && !(*validMagField_) && *validSTR_){ + sensorsAvail = 7; + MDF = 3; + } + else{ + sensorsAvail = 8; //no measurements + validMekf = false; + return RETURN_FAILED; + } + + // If we are here, MEKF will perform + double sigmaSun = 0, sigmaMag = 0, sigmaStr = 0; + sigmaSun = kalmanFilterParameters->sensorNoiseSS; + sigmaMag = kalmanFilterParameters->sensorNoiseMAG; + sigmaStr = kalmanFilterParameters->sensorNoiseSTR; + + double normMagB[3] = {0,0,0}, normSunB[3] = {0,0,0}, + normMagJ[3] = {0,0,0}, normSunJ[3] = {0,0,0}; + VectorOperations::normalize(magneticField_, normMagB, 3); // b2 + VectorOperations::normalize(sunDir_, normSunB, 3); //b1 + VectorOperations::normalize(magFieldJ, normMagJ, 3); //r2 + VectorOperations::normalize(sunDirJ, normSunJ, 3); //r1 + + /*-------GAIN - UPDATE - STEP------*/ + double covMatrix11[3][3] = {{pow(sigmaSun,2),0,0},{0,pow(sigmaSun,2),0},{0,0,pow(sigmaSun,2)}}; + double covMatrix22[3][3] = {{pow(sigmaMag,2),0,0},{0,pow(sigmaMag,2),0},{0,0,pow(sigmaMag,2)}}; + double covMatrix33[3][3] = {{pow(sigmaStr,2),0,0},{0,pow(sigmaStr,2),0},{0,0,pow(sigmaStr,2)}}; + + double dcmBJ[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, + sunEstB[3] = {0,0,0}, magEstB[3] = {0,0,0}; + QuaternionOperations::toDcm(propagatedQuaternion, dcmBJ); + MatrixOperations::multiply(*dcmBJ, normSunJ, sunEstB, 3, 3, 1); + MatrixOperations::multiply(*dcmBJ, normMagJ, magEstB, 3, 3, + 1); + double quatEstErr[3] = {0,0,0}; + + //Measurement Sensitivity Matrix + double measSensMatrix11[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; // ss + double measSensMatrix22[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; // mag + double measSensMatrix33[3][3] = {{1,0,0},{0,1,0},{0,0,1}}; // str + MathOperations::skewMatrix(sunEstB, *measSensMatrix11); + MathOperations::skewMatrix(magEstB, *measSensMatrix22); + + double measVecQuat[3] = {0,0,0}; + if (*validSTR_){ + double quatError[4] = {0,0,0,0}; + double invPropagatedQuat[4] = {0,0,0,0}; + QuaternionOperations::inverse(propagatedQuaternion, invPropagatedQuat); + QuaternionOperations::multiply(quaternionSTR, invPropagatedQuat, quatError); + for (int i = 0 ; i < 3;i++){ + measVecQuat[i]=2*quatError[i]/quatError[3]; + } + } + // Adjust matrices based on valid measurements + double measSensMatrix[MDF][6], measCovMatrix[MDF][MDF], measVec[MDF], + measEstVec[MDF]; + if (sensorsAvail==1){ //All measurements valid + measSensMatrix[0][0] = measSensMatrix11[0][0]; + measSensMatrix[0][1] = measSensMatrix11[0][1]; + measSensMatrix[0][2] = measSensMatrix11[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix11[1][0]; + measSensMatrix[1][1] = measSensMatrix11[1][1]; + measSensMatrix[1][2] = measSensMatrix11[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix11[2][0]; + measSensMatrix[2][1] = measSensMatrix11[2][1]; + measSensMatrix[2][2] = measSensMatrix11[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + measSensMatrix[3][0] = measSensMatrix22[0][0]; + measSensMatrix[3][1] = measSensMatrix22[0][1]; + measSensMatrix[3][2] = measSensMatrix22[0][2]; + measSensMatrix[3][3] = 0; + measSensMatrix[3][4] = 0; + measSensMatrix[3][5] = 0; + measSensMatrix[4][0] = measSensMatrix22[1][0]; + measSensMatrix[4][1] = measSensMatrix22[1][1]; + measSensMatrix[4][2] = measSensMatrix22[1][2]; + measSensMatrix[4][3] = 0; + measSensMatrix[4][4] = 0; + measSensMatrix[4][5] = 0; + measSensMatrix[5][0] = measSensMatrix22[2][0]; + measSensMatrix[5][1] = measSensMatrix22[2][1]; + measSensMatrix[5][2] = measSensMatrix22[2][2]; + measSensMatrix[5][3] = 0; + measSensMatrix[5][4] = 0; + measSensMatrix[5][5] = 0; + measSensMatrix[6][0] = measSensMatrix33[0][0]; + measSensMatrix[6][1] = measSensMatrix33[0][1]; + measSensMatrix[6][2] = measSensMatrix33[0][2]; + measSensMatrix[6][3] = 0; + measSensMatrix[6][4] = 0; + measSensMatrix[6][5] = 0; + measSensMatrix[7][0] = measSensMatrix33[1][0]; + measSensMatrix[7][1] = measSensMatrix33[1][1]; + measSensMatrix[7][2] = measSensMatrix33[1][2]; + measSensMatrix[7][3] = 0; + measSensMatrix[7][4] = 0; + measSensMatrix[7][5] = 0; + measSensMatrix[8][0] = measSensMatrix33[2][0]; + measSensMatrix[8][1] = measSensMatrix33[2][1]; + measSensMatrix[8][2] = measSensMatrix33[2][2]; + measSensMatrix[8][3] = 0; + measSensMatrix[8][4] = 0; + measSensMatrix[8][5] = 0; + + measCovMatrix[0][0] = covMatrix11[0][0]; + measCovMatrix[0][1] = covMatrix11[0][1]; + measCovMatrix[0][2] = covMatrix11[0][2]; + measCovMatrix[0][3] = 0; + measCovMatrix[0][4] = 0; + measCovMatrix[0][5] = 0; + measCovMatrix[0][6] = 0; + measCovMatrix[0][7] = 0; + measCovMatrix[0][8] = 0; + measCovMatrix[1][0] = covMatrix11[1][0]; + measCovMatrix[1][1] = covMatrix11[1][1]; + measCovMatrix[1][2] = covMatrix11[1][2]; + measCovMatrix[1][3] = 0; + measCovMatrix[1][4] = 0; + measCovMatrix[1][5] = 0; + measCovMatrix[1][6] = 0; + measCovMatrix[1][7] = 0; + measCovMatrix[1][8] = 0; + measCovMatrix[2][0] = covMatrix11[2][0]; + measCovMatrix[2][1] = covMatrix11[2][1]; + measCovMatrix[2][2] = covMatrix11[2][2]; + measCovMatrix[2][3] = 0; + measCovMatrix[2][4] = 0; + measCovMatrix[2][5] = 0; + measCovMatrix[2][6] = 0; + measCovMatrix[2][7] = 0; + measCovMatrix[2][8] = 0; + measCovMatrix[3][0] = 0; + measCovMatrix[3][1] = 0; + measCovMatrix[3][2] = 0; + measCovMatrix[3][3] = covMatrix22[0][0]; + measCovMatrix[3][4] = covMatrix22[0][1]; + measCovMatrix[3][5] = covMatrix22[0][2]; + measCovMatrix[3][6] = 0; + measCovMatrix[3][7] = 0; + measCovMatrix[3][8] = 0; + measCovMatrix[4][0] = 0; + measCovMatrix[4][1] = 0; + measCovMatrix[4][2] = 0; + measCovMatrix[4][3] = covMatrix22[1][0]; + measCovMatrix[4][4] = covMatrix22[1][1]; + measCovMatrix[4][5] = covMatrix22[1][2]; + measCovMatrix[4][6] = 0; + measCovMatrix[4][7] = 0; + measCovMatrix[4][8] = 0; + measCovMatrix[5][0] = 0; + measCovMatrix[5][1] = 0; + measCovMatrix[5][2] = 0; + measCovMatrix[5][3] = covMatrix22[2][0]; + measCovMatrix[5][4] = covMatrix22[2][1]; + measCovMatrix[5][5] = covMatrix22[2][2]; + measCovMatrix[5][6] = 0; + measCovMatrix[5][7] = 0; + measCovMatrix[5][8] = 0; + measCovMatrix[6][0] = 0; + measCovMatrix[6][1] = 0; + measCovMatrix[6][2] = 0; + measCovMatrix[6][3] = 0; + measCovMatrix[6][4] = 0; + measCovMatrix[6][5] = 0; + measCovMatrix[6][6] = covMatrix33[0][0]; + measCovMatrix[6][7] = covMatrix33[0][1]; + measCovMatrix[6][8] = covMatrix33[0][2]; + measCovMatrix[7][0] = 0; + measCovMatrix[7][1] = 0; + measCovMatrix[7][2] = 0; + measCovMatrix[7][3] = 0; + measCovMatrix[7][4] = 0; + measCovMatrix[7][5] = 0; + measCovMatrix[7][6] = covMatrix33[1][0]; + measCovMatrix[7][7] = covMatrix33[1][1]; + measCovMatrix[7][8] = covMatrix33[1][2]; + measCovMatrix[8][0] = 0; + measCovMatrix[8][1] = 0; + measCovMatrix[8][2] = 0; + measCovMatrix[8][3] = 0; + measCovMatrix[8][4] = 0; + measCovMatrix[8][5] = 0; + measCovMatrix[8][6] = covMatrix33[2][0]; + measCovMatrix[8][7] = covMatrix33[2][1]; + measCovMatrix[8][8] = covMatrix33[2][2]; + + measVec[0] = normSunB[0]; + measVec[1] = normSunB[1]; + measVec[2] = normSunB[2]; + measVec[3] = normMagB[0]; + measVec[4] = normMagB[1]; + measVec[5] = normMagB[2]; + measVec[6] = measVecQuat[0]; + measVec[7] = measVecQuat[1]; + measVec[8] = measVecQuat[2]; + + measEstVec[0] = sunEstB[0]; + measEstVec[1] = sunEstB[1]; + measEstVec[2] = sunEstB[2]; + measEstVec[3] = magEstB[0]; + measEstVec[4] = magEstB[1]; + measEstVec[5] = magEstB[2]; + measEstVec[6] = quatEstErr[0]; + measEstVec[7] = quatEstErr[1]; + measEstVec[8] = quatEstErr[2]; + + } + else if(sensorsAvail==2){ // ss / mag valid + measSensMatrix[0][0] = measSensMatrix11[0][0]; + measSensMatrix[0][1] = measSensMatrix11[0][1]; + measSensMatrix[0][2] = measSensMatrix11[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix11[1][0]; + measSensMatrix[1][1] = measSensMatrix11[1][1]; + measSensMatrix[1][2] = measSensMatrix11[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix11[2][0]; + measSensMatrix[2][1] = measSensMatrix11[2][1]; + measSensMatrix[2][2] = measSensMatrix11[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + measSensMatrix[3][0] = measSensMatrix22[0][0]; + measSensMatrix[3][1] = measSensMatrix22[0][1]; + measSensMatrix[3][2] = measSensMatrix22[0][2]; + measSensMatrix[3][3] = 0; + measSensMatrix[3][4] = 0; + measSensMatrix[3][5] = 0; + measSensMatrix[4][0] = measSensMatrix22[1][0]; + measSensMatrix[4][1] = measSensMatrix22[1][1]; + measSensMatrix[4][2] = measSensMatrix22[1][2]; + measSensMatrix[4][3] = 0; + measSensMatrix[4][4] = 0; + measSensMatrix[4][5] = 0; + measSensMatrix[5][0] = measSensMatrix22[2][0]; + measSensMatrix[5][1] = measSensMatrix22[2][1]; + measSensMatrix[5][2] = measSensMatrix22[2][2]; + measSensMatrix[5][3] = 0; + measSensMatrix[5][4] = 0; + measSensMatrix[5][5] = 0; + + measCovMatrix[0][0] = covMatrix11[0][0]; + measCovMatrix[0][1] = covMatrix11[0][1]; + measCovMatrix[0][2] = covMatrix11[0][2]; + measCovMatrix[0][3] = 0; + measCovMatrix[0][4] = 0; + measCovMatrix[0][5] = 0; + measCovMatrix[1][0] = covMatrix11[1][0]; + measCovMatrix[1][1] = covMatrix11[1][1]; + measCovMatrix[1][2] = covMatrix11[1][2]; + measCovMatrix[1][3] = 0; + measCovMatrix[1][4] = 0; + measCovMatrix[1][5] = 0; + measCovMatrix[2][0] = covMatrix11[2][0]; + measCovMatrix[2][1] = covMatrix11[2][1]; + measCovMatrix[2][2] = covMatrix11[2][2]; + measCovMatrix[2][3] = 0; + measCovMatrix[2][4] = 0; + measCovMatrix[2][5] = 0; + measCovMatrix[3][0] = 0; + measCovMatrix[3][1] = 0; + measCovMatrix[3][2] = 0; + measCovMatrix[3][3] = covMatrix22[0][0]; + measCovMatrix[3][4] = covMatrix22[0][1]; + measCovMatrix[3][5] = covMatrix22[0][2]; + measCovMatrix[4][0] = 0; + measCovMatrix[4][1] = 0; + measCovMatrix[4][2] = 0; + measCovMatrix[4][3] = covMatrix22[1][0]; + measCovMatrix[4][4] = covMatrix22[1][1]; + measCovMatrix[4][5] = covMatrix22[1][2]; + measCovMatrix[5][0] = 0; + measCovMatrix[5][1] = 0; + measCovMatrix[5][2] = 0; + measCovMatrix[5][3] = covMatrix22[2][0]; + measCovMatrix[5][4] = covMatrix22[2][1]; + measCovMatrix[5][5] = covMatrix22[2][2]; + + measVec[0] = normSunB[0]; + measVec[1] = normSunB[1]; + measVec[2] = normSunB[2]; + measVec[3] = normMagB[0]; + measVec[4] = normMagB[1]; + measVec[5] = normMagB[2]; + + measEstVec[0] = sunEstB[0]; + measEstVec[1] = sunEstB[1]; + measEstVec[2] = sunEstB[2]; + measEstVec[3] = magEstB[0]; + measEstVec[4] = magEstB[1]; + measEstVec[5] = magEstB[2]; + + } + else if(sensorsAvail==3){ // ss / str valid + + measSensMatrix[0][0] = measSensMatrix11[0][0]; + measSensMatrix[0][1] = measSensMatrix11[0][1]; + measSensMatrix[0][2] = measSensMatrix11[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix11[1][0]; + measSensMatrix[1][1] = measSensMatrix11[1][1]; + measSensMatrix[1][2] = measSensMatrix11[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix11[2][0]; + measSensMatrix[2][1] = measSensMatrix11[2][1]; + measSensMatrix[2][2] = measSensMatrix11[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + measSensMatrix[3][0] = measSensMatrix33[0][0]; + measSensMatrix[3][1] = measSensMatrix33[0][1]; + measSensMatrix[3][2] = measSensMatrix33[0][2]; + measSensMatrix[3][3] = 0; + measSensMatrix[3][4] = 0; + measSensMatrix[3][5] = 0; + measSensMatrix[4][0] = measSensMatrix33[1][0]; + measSensMatrix[4][1] = measSensMatrix33[1][1]; + measSensMatrix[4][2] = measSensMatrix33[1][2]; + measSensMatrix[4][3] = 0; + measSensMatrix[4][4] = 0; + measSensMatrix[4][5] = 0; + measSensMatrix[5][0] = measSensMatrix33[2][0]; + measSensMatrix[5][1] = measSensMatrix33[2][1]; + measSensMatrix[5][2] = measSensMatrix33[2][2]; + measSensMatrix[5][3] = 0; + measSensMatrix[5][4] = 0; + measSensMatrix[5][5] = 0; + + measCovMatrix[0][0] = covMatrix11[0][0]; + measCovMatrix[0][1] = covMatrix11[0][1]; + measCovMatrix[0][2] = covMatrix11[0][2]; + measCovMatrix[0][3] = 0; + measCovMatrix[0][4] = 0; + measCovMatrix[0][5] = 0; + measCovMatrix[1][0] = covMatrix11[1][0]; + measCovMatrix[1][1] = covMatrix11[1][1]; + measCovMatrix[1][2] = covMatrix11[1][2]; + measCovMatrix[1][3] = 0; + measCovMatrix[1][4] = 0; + measCovMatrix[1][5] = 0; + measCovMatrix[2][0] = covMatrix11[2][0]; + measCovMatrix[2][1] = covMatrix11[2][1]; + measCovMatrix[2][2] = covMatrix11[2][2]; + measCovMatrix[2][3] = 0; + measCovMatrix[2][4] = 0; + measCovMatrix[2][5] = 0; + measCovMatrix[3][0] = 0; + measCovMatrix[3][1] = 0; + measCovMatrix[3][2] = 0; + measCovMatrix[3][3] = covMatrix33[0][0]; + measCovMatrix[3][4] = covMatrix33[0][1]; + measCovMatrix[3][5] = covMatrix33[0][2]; + measCovMatrix[4][0] = 0; + measCovMatrix[4][1] = 0; + measCovMatrix[4][2] = 0; + measCovMatrix[4][3] = covMatrix33[1][0]; + measCovMatrix[4][4] = covMatrix33[1][1]; + measCovMatrix[4][5] = covMatrix33[1][2]; + measCovMatrix[5][0] = 0; + measCovMatrix[5][1] = 0; + measCovMatrix[5][2] = 0; + measCovMatrix[5][3] = covMatrix33[2][0]; + measCovMatrix[5][4] = covMatrix33[2][1]; + measCovMatrix[5][5] = covMatrix33[2][2]; + + measVec[0] = normSunB[0]; + measVec[1] = normSunB[1]; + measVec[2] = normSunB[2]; + measVec[3] = measVecQuat[0]; + measVec[4] = measVecQuat[1]; + measVec[5] = measVecQuat[2]; + + measEstVec[0] = sunEstB[0]; + measEstVec[1] = sunEstB[1]; + measEstVec[2] = sunEstB[2]; + measEstVec[3] = quatEstErr[0]; + measEstVec[4] = quatEstErr[1]; + measEstVec[5] = quatEstErr[2]; + + } + else if (sensorsAvail == 4){ // mag / str avail + + measSensMatrix[0][0] = measSensMatrix22[0][0]; + measSensMatrix[0][1] = measSensMatrix22[0][1]; + measSensMatrix[0][2] = measSensMatrix22[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix22[1][0]; + measSensMatrix[1][1] = measSensMatrix22[1][1]; + measSensMatrix[1][2] = measSensMatrix22[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix22[2][0]; + measSensMatrix[2][1] = measSensMatrix22[2][1]; + measSensMatrix[2][2] = measSensMatrix22[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + measSensMatrix[3][0] = measSensMatrix33[0][0]; + measSensMatrix[3][1] = measSensMatrix33[0][1]; + measSensMatrix[3][2] = measSensMatrix33[0][2]; + measSensMatrix[3][3] = 0; + measSensMatrix[3][4] = 0; + measSensMatrix[3][5] = 0; + measSensMatrix[4][0] = measSensMatrix33[1][0]; + measSensMatrix[4][1] = measSensMatrix33[1][1]; + measSensMatrix[4][2] = measSensMatrix33[1][2]; + measSensMatrix[4][3] = 0; + measSensMatrix[4][4] = 0; + measSensMatrix[4][5] = 0; + measSensMatrix[5][0] = measSensMatrix33[2][0]; + measSensMatrix[5][1] = measSensMatrix33[2][1]; + measSensMatrix[5][2] = measSensMatrix33[2][2]; + measSensMatrix[5][3] = 0; + measSensMatrix[5][4] = 0; + measSensMatrix[5][5] = 0; + + measCovMatrix[0][0] = covMatrix22[0][0]; + measCovMatrix[0][1] = covMatrix22[0][1]; + measCovMatrix[0][2] = covMatrix22[0][2]; + measCovMatrix[0][3] = 0; + measCovMatrix[0][4] = 0; + measCovMatrix[0][5] = 0; + measCovMatrix[1][0] = covMatrix22[1][0]; + measCovMatrix[1][1] = covMatrix22[1][1]; + measCovMatrix[1][2] = covMatrix22[1][2]; + measCovMatrix[1][3] = 0; + measCovMatrix[1][4] = 0; + measCovMatrix[1][5] = 0; + measCovMatrix[2][0] = covMatrix22[2][0]; + measCovMatrix[2][1] = covMatrix22[2][1]; + measCovMatrix[2][2] = covMatrix22[2][2]; + measCovMatrix[2][3] = 0; + measCovMatrix[2][4] = 0; + measCovMatrix[2][5] = 0; + measCovMatrix[3][0] = 0; + measCovMatrix[3][1] = 0; + measCovMatrix[3][2] = 0; + measCovMatrix[3][3] = covMatrix33[0][0]; + measCovMatrix[3][4] = covMatrix33[0][1]; + measCovMatrix[3][5] = covMatrix33[0][2]; + measCovMatrix[4][0] = 0; + measCovMatrix[4][1] = 0; + measCovMatrix[4][2] = 0; + measCovMatrix[4][3] = covMatrix33[1][0]; + measCovMatrix[4][4] = covMatrix33[1][1]; + measCovMatrix[4][5] = covMatrix33[1][2]; + measCovMatrix[5][0] = 0; + measCovMatrix[5][1] = 0; + measCovMatrix[5][2] = 0; + measCovMatrix[5][3] = covMatrix33[2][0]; + measCovMatrix[5][4] = covMatrix33[2][1]; + measCovMatrix[5][5] = covMatrix33[2][2]; + + measVec[0] = normMagB[0]; + measVec[1] = normMagB[1]; + measVec[2] = normMagB[2]; + measVec[3] = measVecQuat[0]; + measVec[4] = measVecQuat[1]; + measVec[5] = measVecQuat[2]; + + measEstVec[0] = magEstB[0]; + measEstVec[1] = magEstB[1]; + measEstVec[2] = magEstB[2]; + measEstVec[3] = quatEstErr[0]; + measEstVec[4] = quatEstErr[1]; + measEstVec[5] = quatEstErr[2]; + + } + else if (sensorsAvail == 5){ // only ss + + measSensMatrix[0][0] = measSensMatrix11[0][0]; + measSensMatrix[0][1] = measSensMatrix11[0][1]; + measSensMatrix[0][2] = measSensMatrix11[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix11[1][0]; + measSensMatrix[1][1] = measSensMatrix11[1][1]; + measSensMatrix[1][2] = measSensMatrix11[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix11[2][0]; + measSensMatrix[2][1] = measSensMatrix11[2][1]; + measSensMatrix[2][2] = measSensMatrix11[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + + measCovMatrix[0][0] = covMatrix11[0][0]; + measCovMatrix[0][1] = covMatrix11[0][1]; + measCovMatrix[0][2] = covMatrix11[0][2]; + measCovMatrix[1][0] = covMatrix11[1][0]; + measCovMatrix[1][1] = covMatrix11[1][1]; + measCovMatrix[1][2] = covMatrix11[1][2]; + measCovMatrix[2][0] = covMatrix11[2][0]; + measCovMatrix[2][1] = covMatrix11[2][1]; + measCovMatrix[2][2] = covMatrix11[2][2]; + + measVec[0] = normSunB[0]; + measVec[1] = normSunB[1]; + measVec[2] = normSunB[2]; + + measEstVec[0] = sunEstB[0]; + measEstVec[1] = sunEstB[1]; + measEstVec[2] = sunEstB[2]; + + } + else if (sensorsAvail == 6){ // only mag + + measSensMatrix[0][0] = measSensMatrix22[0][0]; + measSensMatrix[0][1] = measSensMatrix22[0][1]; + measSensMatrix[0][2] = measSensMatrix22[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix22[1][0]; + measSensMatrix[1][1] = measSensMatrix22[1][1]; + measSensMatrix[1][2] = measSensMatrix22[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix22[2][0]; + measSensMatrix[2][1] = measSensMatrix22[2][1]; + measSensMatrix[2][2] = measSensMatrix22[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + + measCovMatrix[0][0] = covMatrix22[0][0]; + measCovMatrix[0][1] = covMatrix22[0][1]; + measCovMatrix[0][2] = covMatrix22[0][2]; + measCovMatrix[1][0] = covMatrix22[1][0]; + measCovMatrix[1][1] = covMatrix22[1][1]; + measCovMatrix[1][2] = covMatrix22[1][2]; + measCovMatrix[2][0] = covMatrix22[2][0]; + measCovMatrix[2][1] = covMatrix22[2][1]; + measCovMatrix[2][2] = covMatrix22[2][2]; + + measVec[0] = normMagB[0]; + measVec[1] = normMagB[1]; + measVec[2] = normMagB[2]; + + measEstVec[0] = magEstB[0]; + measEstVec[1] = magEstB[1]; + measEstVec[2] = magEstB[2]; + + } + else if (sensorsAvail == 7){ // only str + + measSensMatrix[0][0] = measSensMatrix33[0][0]; + measSensMatrix[0][1] = measSensMatrix33[0][1]; + measSensMatrix[0][2] = measSensMatrix33[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix33[1][0]; + measSensMatrix[1][1] = measSensMatrix33[1][1]; + measSensMatrix[1][2] = measSensMatrix33[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix33[2][0]; + measSensMatrix[2][1] = measSensMatrix33[2][1]; + measSensMatrix[2][2] = measSensMatrix33[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + + measCovMatrix[0][0] = covMatrix33[0][0]; + measCovMatrix[0][1] = covMatrix33[0][1]; + measCovMatrix[0][2] = covMatrix33[0][2]; + measCovMatrix[1][0] = covMatrix33[1][0]; + measCovMatrix[1][1] = covMatrix33[1][1]; + measCovMatrix[1][2] = covMatrix33[1][2]; + measCovMatrix[2][0] = covMatrix33[2][0]; + measCovMatrix[2][1] = covMatrix33[2][1]; + measCovMatrix[2][2] = covMatrix33[2][2]; + + measVec[0] = measVecQuat[0]; + measVec[1] = measVecQuat[1]; + measVec[2] = measVecQuat[2]; + + measEstVec[0] = quatEstErr[0]; + measEstVec[1] = quatEstErr[1]; + measEstVec[2] = quatEstErr[2]; + + } + // Kalman Gain: [K = P * H' / (H * P * H' + R)] + double kalmanGain[6][MDF] = {{0}}, kalmanGain1[6][MDF] = {{0}}; + + double measSensMatrixTrans[6][MDF], residualCov[MDF][MDF], + residualCov1[6][MDF]; + // H * P * H' + MatrixOperations::transpose(*measSensMatrix,*measSensMatrixTrans,6,MDF); + MatrixOperations::multiply(*initialCovarianceMatrix,*measSensMatrixTrans,*residualCov1,6,6,MDF); + MatrixOperations::multiply(*measSensMatrix,*residualCov1,*residualCov,MDF,6,MDF); + // negative values, restrictions ? + // (H * P * H' + R) + MatrixOperations::add(*residualCov, *measCovMatrix, *residualCov, MDF, MDF); + // <> + double invResidualCov1[MDF] = {0}; + double invResidualCov[MDF][MDF] = {{0}}; + int inversionFailed = CholeskyDecomposition::invertCholesky(*residualCov,*invResidualCov,invResidualCov1,MDF); + if(inversionFailed) + { + validMekf = false; + return KALMAN_INVERSION_FAILED; // RETURN VALUE ? -- Like: Kalman Inversion Failed + } + + + // [K = P * H' / (H * P * H' + R)] + MatrixOperations::multiply(*measSensMatrixTrans,*invResidualCov,*kalmanGain1,6,MDF,MDF); + MatrixOperations::multiply(*initialCovarianceMatrix,*kalmanGain1,*kalmanGain,6,6,MDF); + + /* ------- UPDATE -STEP ---------*/ + + // Update Covariance Matrix: P_plus = (I-K*H)*P_min + double covMatPlus[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 identityMatrix[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}}; + double updateCov1[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}}; + MatrixOperations::multiply(*kalmanGain,*measSensMatrix,*updateCov1,6,MDF,MDF); + MatrixOperations::subtract(*identityMatrix,*updateCov1,*updateCov1,6,6); + MatrixOperations::multiply(*updateCov1,*initialCovarianceMatrix,*covMatPlus,6,6,6); + + // Error State Vector + double errStateVec[6] = {0,0,0,0,0,0}; + double errStateVec1[MDF] = {0}; + VectorOperations::subtract(measVec,measEstVec,errStateVec1,MDF); + MatrixOperations::multiply(*kalmanGain,errStateVec1,errStateVec,6,MDF,1); + + double errStateQuat[3] = {errStateVec[0], errStateVec[1], errStateVec[2]}; + double errStateGyroBias[3] = {errStateVec[3], errStateVec[4], errStateVec[5]}; + + // State Vector Elements + double xi1[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, + xi2[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; + MathOperations::skewMatrix(propagatedQuaternion, *xi2); + double identityMatrix3[3][3] = {{1,0,0},{0,1,0},{0,0,1}}; + MatrixOperations::multiplyScalar(*identityMatrix3, propagatedQuaternion[3], *xi1, 3, 3); + MatrixOperations::add(*xi1, *xi2, *xi1, 3, 3); + double xi[4][3] = {{xi1[0][0],xi1[0][1],xi1[0][2]}, + {xi1[1][0],xi1[1][1],xi1[1][2]}, + {xi1[2][0],xi1[2][1],xi1[2][2]}, + {-propagatedQuaternion[0],-propagatedQuaternion[1],-propagatedQuaternion[2]}}; + + double errQuatTerm[4] = {0,0,0,0}; + MatrixOperations::multiply(*xi, errStateQuat, errQuatTerm, 4, 3, 1); + VectorOperations::mulScalar(errQuatTerm, 0.5, errQuatTerm, 4); + VectorOperations::add(propagatedQuaternion, errQuatTerm, quatBJ, 4); + VectorOperations::normalize(quatBJ, quatBJ, 4); + + outputQuat[0] = quatBJ[0]; + outputQuat[1] = quatBJ[1]; + outputQuat[2] = quatBJ[2]; + outputQuat[3] = quatBJ[3]; + + double updatedGyroBias[3] = {0,0,0}; + VectorOperations::add(biasRMU, errStateGyroBias, updatedGyroBias, 3); + // Bias RMU State + biasRMU[0] = updatedGyroBias[0]; + biasRMU[1] = updatedGyroBias[1]; + biasRMU[2] = updatedGyroBias[2]; + + + /* ----------- PROPAGATION ----------*/ + //double sigmaU = kalmanFilterParameters->sensorNoiseBsRMU; + //double sigmaV = kalmanFilterParameters->sensorNoiseArwRmu; + double sigmaU = 3*3.141/180/3600; + double sigmaV = 3*0.0043*3.141/sqrt(10)/180; + + 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}}; + double rotRateEst[3] = {0,0,0}; + VectorOperations::subtract(rateRMUs_, updatedGyroBias, rotRateEst, 3); + double normRotEst =VectorOperations::norm(rotRateEst, 3); + double crossRotEst[3][3] = {{0,-rotRateEst[2],rotRateEst[1]}, + {rotRateEst[2],0,-rotRateEst[0]}, + {-rotRateEst[1],rotRateEst[0],0}}; + + // Corrected Sat Rate via Bias + outputSatRate[0] = rotRateEst[0]; + outputSatRate[1] = rotRateEst[1]; + outputSatRate[2] = rotRateEst[2]; + + // Discrete Process Noise Covariance Q + double discProcessNoiseCov[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 covQ1[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, + covQ2[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, + covQ3[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, + transCovQ2[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; + if(normRotEst*sampleTime< 3.141/10){ + double fact1 = sampleTime*pow(sigmaV,2)+pow(sampleTime,3)*pow(sigmaU,2/3); + MatrixOperations::multiplyScalar(*identityMatrix3, fact1, *covQ1, 3, 3); + double fact2 = -(0.5*pow(sampleTime,2)*pow(sigmaU,2)); + MatrixOperations::multiplyScalar(*identityMatrix3, fact2, *covQ2, 3, 3); + MatrixOperations::transpose(*covQ2, *transCovQ2, 3); + double fact3 = sampleTime*pow(sigmaU,2); + MatrixOperations::multiplyScalar(*identityMatrix3, fact3, *covQ3, 3, 3); + + discProcessNoiseCov[0][0] = covQ1[0][0]; + discProcessNoiseCov[0][1] = covQ1[0][1]; + discProcessNoiseCov[0][2] = covQ1[0][2]; + discProcessNoiseCov[0][3] = covQ2[0][0]; + discProcessNoiseCov[0][4] = covQ2[0][1]; + discProcessNoiseCov[0][5] = covQ2[0][2]; + discProcessNoiseCov[1][0] = covQ1[1][0]; + discProcessNoiseCov[1][1] = covQ1[1][1]; + discProcessNoiseCov[1][2] = covQ1[1][2]; + discProcessNoiseCov[1][3] = covQ2[1][0]; + discProcessNoiseCov[1][4] = covQ2[1][1]; + discProcessNoiseCov[1][5] = covQ2[1][2]; + discProcessNoiseCov[2][0] = covQ1[2][0]; + discProcessNoiseCov[2][1] = covQ1[2][1]; + discProcessNoiseCov[2][2] = covQ1[2][2]; + discProcessNoiseCov[2][3] = covQ2[2][0]; + discProcessNoiseCov[2][4] = covQ2[2][1]; + discProcessNoiseCov[2][5] = covQ2[2][2]; + discProcessNoiseCov[3][0] = transCovQ2[0][0]; + discProcessNoiseCov[3][1] = transCovQ2[0][1]; + discProcessNoiseCov[3][2] = transCovQ2[0][2]; + discProcessNoiseCov[3][3] = covQ3[0][0]; + discProcessNoiseCov[3][4] = covQ3[0][1]; + discProcessNoiseCov[3][5] = covQ3[0][2]; + discProcessNoiseCov[4][0] = transCovQ2[1][0]; + discProcessNoiseCov[4][1] = transCovQ2[1][1]; + discProcessNoiseCov[4][2] = transCovQ2[1][2]; + discProcessNoiseCov[4][3] = covQ3[1][0]; + discProcessNoiseCov[4][4] = covQ3[1][1]; + discProcessNoiseCov[4][5] = covQ3[1][2]; + discProcessNoiseCov[5][0] = transCovQ2[2][0]; + discProcessNoiseCov[5][1] = transCovQ2[2][1]; + discProcessNoiseCov[5][2] = transCovQ2[2][2]; + discProcessNoiseCov[5][3] = covQ3[2][0]; + discProcessNoiseCov[5][4] = covQ3[2][1]; + discProcessNoiseCov[5][5] = covQ3[2][2]; + } + else{ + //double fact1 = sampleTime*pow(sigmaV,2); + double covQ11[3][3],covQ12[3][3],covQ13[3][3]; + //MatrixOperations::multiplyScalar(*identityMatrix3, fact1, *covQ1, 3, 3); + double fact1 = (2*normRotEst+sampleTime-2*sin(normRotEst*sampleTime) + -pow(normRotEst,3)/3*pow(sampleTime,3))/pow(normRotEst,5); + MatrixOperations::multiply(*crossRotEst, *crossRotEst, *covQ11, 3, 3, 3); + MatrixOperations::multiplyScalar(*covQ11, fact1, *covQ11, 3, 3); + double fact2 = pow(sampleTime,3); + MatrixOperations::multiplyScalar(*identityMatrix3, fact2, *covQ12, 3, 3); + MatrixOperations::subtract(*covQ12, *covQ11, *covQ11, 3, 3); + double fact3 = sampleTime*pow(sigmaV,2); + MatrixOperations::multiplyScalar(*identityMatrix3, fact3, *covQ13, 3, 3); + MatrixOperations::add(*covQ13, *covQ11, *covQ1, 3, 3); + + double covQ21[3][3], covQ22[3][3], covQ23[3][3]; + double fact4 = (0.5*pow(normRotEst,2)*pow(sampleTime,2) + +cos(normRotEst*sampleTime)-1)/pow(normRotEst,4); + MatrixOperations::multiply(*crossRotEst, *crossRotEst, *covQ21, 3, 3, 3); + MatrixOperations::multiplyScalar(*covQ21, fact4, *covQ21, 3, 3); + double fact5 = 0.5*pow(sampleTime,2); + MatrixOperations::multiplyScalar(*identityMatrix3, fact5, *covQ22, 3, 3); + MatrixOperations::add(*covQ22, *covQ21, *covQ21, 3, 3); + double fact6 = normRotEst*sampleTime-sin(normRotEst*sampleTime)/pow(normRotEst,3); + MatrixOperations::multiplyScalar(*crossRotEst, fact6, *covQ23, 3, 3); + MatrixOperations::subtract(*covQ23, *covQ21, *covQ21, 3, 3); + double fact7 = pow(sigmaU,2); + MatrixOperations::multiplyScalar(*covQ21, fact7, *covQ2, 3, 3); + + MatrixOperations::multiplyScalar(*identityMatrix3, fact7, *covQ3, 3, 3); + + discProcessNoiseCov[0][0] = covQ1[0][0]; + discProcessNoiseCov[0][1] = covQ1[0][1]; + discProcessNoiseCov[0][2] = covQ1[0][2]; + discProcessNoiseCov[0][3] = covQ2[0][0]; + discProcessNoiseCov[0][4] = covQ2[0][1]; + discProcessNoiseCov[0][5] = covQ2[0][2]; + discProcessNoiseCov[1][0] = covQ1[1][0]; + discProcessNoiseCov[1][1] = covQ1[1][1]; + discProcessNoiseCov[1][2] = covQ1[1][2]; + discProcessNoiseCov[1][3] = covQ2[1][0]; + discProcessNoiseCov[1][4] = covQ2[1][1]; + discProcessNoiseCov[1][5] = covQ2[1][2]; + discProcessNoiseCov[2][0] = covQ1[2][0]; + discProcessNoiseCov[2][1] = covQ1[2][1]; + discProcessNoiseCov[2][2] = covQ1[2][2]; + discProcessNoiseCov[2][3] = covQ2[2][0]; + discProcessNoiseCov[2][4] = covQ2[2][1]; + discProcessNoiseCov[2][5] = covQ2[2][2]; + discProcessNoiseCov[3][0] = covQ2[0][0]; + discProcessNoiseCov[3][1] = covQ2[0][1]; + discProcessNoiseCov[3][2] = covQ2[0][2]; + discProcessNoiseCov[3][3] = covQ3[0][0]; + discProcessNoiseCov[3][4] = covQ3[0][1]; + discProcessNoiseCov[3][5] = covQ3[0][2]; + discProcessNoiseCov[4][0] = covQ2[1][0]; + discProcessNoiseCov[4][1] = covQ2[1][1]; + discProcessNoiseCov[4][2] = covQ2[1][2]; + discProcessNoiseCov[4][3] = covQ3[1][0]; + discProcessNoiseCov[4][4] = covQ3[1][1]; + discProcessNoiseCov[4][5] = covQ3[1][2]; + discProcessNoiseCov[5][0] = covQ2[2][0]; + discProcessNoiseCov[5][1] = covQ2[2][1]; + discProcessNoiseCov[5][2] = covQ2[2][2]; + discProcessNoiseCov[5][3] = covQ3[2][0]; + discProcessNoiseCov[5][4] = covQ3[2][1]; + discProcessNoiseCov[5][5] = covQ3[2][2]; + } + + // State Transition Matrix phi + double phi1[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, + phi2[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, + 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[3][3],phi12[3][3]; + double fact1 = sin(normRotEst*sampleTime); + MatrixOperations::multiplyScalar(*crossRotEst, fact1, *phi11, 3, 3); + double fact2 = (1-cos(normRotEst*sampleTime))/pow(normRotEst,2); + MatrixOperations::multiply(*crossRotEst, *crossRotEst, *phi12, 3, 3, 3); + MatrixOperations::multiplyScalar(*phi12, fact2, *phi12, 3, 3); + MatrixOperations::subtract(*identityMatrix3, *phi11, *phi11, 3, 3); + MatrixOperations::add(*phi11, *phi12, *phi1, 3, 3); + + double phi21[3][3],phi22[3][3]; + MatrixOperations::multiplyScalar(*crossRotEst, fact2, *phi21, 3, 3); + MatrixOperations::multiplyScalar(*identityMatrix3, sampleTime, *phi22, 3, 3); + MatrixOperations::subtract(*phi21, *phi22, *phi21, 3, 3); + double fact3 = (normRotEst*sampleTime-sin(normRotEst*sampleTime)/pow(normRotEst,3)); + MatrixOperations::multiply(*crossRotEst, *crossRotEst, *phi22, 3, 3, 3); + MatrixOperations::multiplyScalar(*phi22, fact3, *phi22, 3, 3); + MatrixOperations::subtract(*phi21, *phi22, *phi2, 3, 3); + + phi[0][0] = phi1[0][0]; + phi[0][1] = phi1[0][1]; + phi[0][2] = phi1[0][2]; + phi[0][3] = phi2[0][0]; + phi[0][4] = phi2[0][1]; + phi[0][5] = phi2[0][2]; + phi[1][0] = phi1[1][0]; + phi[1][1] = phi1[1][1]; + phi[1][2] = phi1[1][2]; + phi[1][3] = phi2[1][0]; + phi[1][4] = phi2[1][1]; + phi[1][5] = phi2[1][2]; + phi[2][0] = phi1[2][0]; + phi[2][1] = phi1[2][1]; + phi[2][2] = phi1[2][2]; + phi[2][3] = phi2[2][0]; + phi[2][4] = phi2[2][1]; + phi[2][5] = phi2[2][2]; + + // Propagated Quaternion + double rotSin[3] = {0,0,0}, + omega1[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; + VectorOperations::mulScalar(rotRateEst, sinFac, rotSin, 3); + + double skewSin[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MathOperations::skewMatrix(rotSin, *skewSin); + + MatrixOperations::multiplyScalar(*identityMatrix3, rotCos, *omega1, 3, 3); + MatrixOperations::subtract(*omega1, *skewSin, *omega1, 3, 3); + double omega[4][4] = {{omega1[0][0],omega1[0][1],omega1[0][2],rotSin[0]}, + {omega1[1][0],omega1[1][1],omega1[1][2],rotSin[1]}, + {omega1[2][0],omega1[2][1],omega1[2][2],rotSin[2]}, + {-rotSin[0],-rotSin[1],-rotSin[2],rotCos}}; + MatrixOperations::multiply(*omega, quatBJ, propagatedQuaternion, 4, 4, 1); + + // Update Covariance Matrix + double cov1[6][6], cov2[6][6], transDiscTimeMatrix[6][6], + transPhi[6][6]; + MatrixOperations::transpose(*discTimeMatrix, *transDiscTimeMatrix, 6); + MatrixOperations::multiply(*discProcessNoiseCov, *transDiscTimeMatrix, *cov1, 6, 6, 6); + MatrixOperations::multiply(*discTimeMatrix, *cov1, *cov1, 6, 6, 6); + + MatrixOperations::transpose(*phi, *transPhi, 6); + MatrixOperations::multiply(*covMatPlus, *transPhi, *cov2, 6, 6, 6); + MatrixOperations::multiply(*phi, *cov2, *cov2, 6, 6, 6); + + MatrixOperations::add(*cov2, *cov1, *initialCovarianceMatrix, 6, 6); + validMekf = true; + + + // Discrete Time Step + + // Check for new data in measurement -> SensorProcessing ? + + return RETURN_OK; +} diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.h b/mission/controller/acs/MultiplicativeKalmanFilter.h new file mode 100644 index 00000000..d4370ad3 --- /dev/null +++ b/mission/controller/acs/MultiplicativeKalmanFilter.h @@ -0,0 +1,107 @@ +/* + * MultiplicativeKalmanFilter.h + * + * Created on: 4 Feb 2022 + * Author: Robin Marquardt + * + * @brief: This class handles the calculation of an estimated quaternion and the gyro bias by + * means of the spacecraft attitude sensors + * + * @note: A description of the used algorithms can be found in the bachelor thesis of Robin Marquardt + * https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_Studenten/Marquardt_Robin&openfile=500811 + */ + +#ifndef MULTIPLICATIVEKALMANFILTER_H_ +#define MULTIPLICATIVEKALMANFILTER_H_ + +#include //uint8_t +#include /*purpose, timeval ?*/ +#include "acs/config/classIds.h" +//#include <_timeval.h> + +#include "AcsParameters.h" + +class MultiplicativeKalmanFilter : public HasReturnvaluesIF { +public: + /* @brief: Constructor + * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters + */ + MultiplicativeKalmanFilter(AcsParameters *acsParameters_); + virtual ~MultiplicativeKalmanFilter(); + + void reset(); // NOT YET DEFINED - should only reset all mekf variables + + /* @brief: init() - This function initializes the Kalman Filter and will provide the first quaternion through + * the QUEST algorithm + * @param: magneticField_ magnetic field vector in the body frame + * sunDir_ sun direction vector in the body frame + * sunDirJ sun direction vector in the ECI frame + * magFieldJ magnetic field vector in the ECI frame + */ + void 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); + + /* @brief: mekfEst() - This function calculates the quaternion and gyro bias of the Kalman Filter for the current step + * after the initalization + * @param: quaternionSTR Star Tracker Quaternion between from body to ECI frame + * rateRMUs_ Estimated satellite rotation rate from the Rate Measurement Units [rad/s] + * magneticField_ magnetic field vector in the body frame + * sunDir_ sun direction vector in the body frame + * sunDirJ sun direction vector in the ECI frame + * magFieldJ magnetic field vector in the ECI frame + * outputQuat Stores the calculated quaternion + * outputSatRate Stores the adjusted satellite rate + * @return ReturnValue_t Feedback of this class, KALMAN_NO_RMU_MEAS if no satellite rate from the sensors was provided, + * KALMAN_NO_MODEL if no sunDirJ or magFieldJ was given from the model calculations, + * KALMAN_INVERSION_FAILED if the calculation of the Gain matrix was not possible, + * RETURN_OK else + */ + ReturnValue_t mekfEst( + const double *quaternionSTR, const bool *validSTR_, + const double *rateRMUs_, const bool *validRMUs_, + 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 *outputQuat, double *outputSatRate); + + + // Declaration of Events (like init) and memberships + //static const uint8_t INTERFACE_ID = CLASS_ID::MEKF; //CLASS IDS ND (/config/returnvalues/classIDs.h) + //static const Event RESET = MAKE_EVENT(1,severity::INFO);//typedef uint32_t Event (Event.h), should be + // resetting Mekf + static const uint8_t INTERFACE_ID = CLASS_ID::KALMAN; + static const ReturnValue_t KALMAN_NO_RMU_MEAS = MAKE_RETURN_CODE(0x01); + static const ReturnValue_t KALMAN_NO_MODEL = MAKE_RETURN_CODE(0x02); + static const ReturnValue_t KALMAN_INVERSION_FAILED = MAKE_RETURN_CODE(0x03); + +private: +/*Parameters*/ + AcsParameters::InertiaEIVE* inertiaEIVE; + AcsParameters::KalmanFilterParameters* kalmanFilterParameters; + double quaternion_STR_SB[4]; + bool validInit; + double sampleTime = 0.1; + + +/*States*/ + double initialQuaternion[4]; /*after reset?QUEST*/ + double initialCovarianceMatrix[6][6];/*after reset?QUEST*/ + double propagatedQuaternion[4]; /*Filter Quaternion for next step*/ + bool validMekf; + uint8_t sensorsAvail; + +/*Outputs*/ + double quatBJ[4]; /* Output Quaternion */ + double biasRMU[3]; /*Between measured and estimated sat Rate*/ +/*Parameter INIT*/ + //double alpha, gamma, beta; +/*Functions*/ + void loadAcsParameters(AcsParameters *acsParameters_); +}; + + + +#endif /* ACS_MULTIPLICATIVEKALMANFILTER_H_ */ -- 2.34.1 From a95f7ff8b013d48a3953d243fef0ef720604a7a4 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 19 Sep 2022 14:36:08 +0200 Subject: [PATCH 007/101] added CholeskyDecomposition --- .../acs/MultiplicativeKalmanFilter.cpp | 4 +- .../acs/util/CholeskyDecomposition.h | 102 ++++++++++++++++++ 2 files changed, 104 insertions(+), 2 deletions(-) create mode 100644 mission/controller/acs/util/CholeskyDecomposition.h diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.cpp b/mission/controller/acs/MultiplicativeKalmanFilter.cpp index 5d895566..5a546409 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.cpp +++ b/mission/controller/acs/MultiplicativeKalmanFilter.cpp @@ -12,8 +12,8 @@ #include #include #include "MultiplicativeKalmanFilter.h" -#include -#include +#include +#include /*Initialisation of values for parameters in constructor*/ MultiplicativeKalmanFilter::MultiplicativeKalmanFilter(AcsParameters *acsParameters_) : diff --git a/mission/controller/acs/util/CholeskyDecomposition.h b/mission/controller/acs/util/CholeskyDecomposition.h new file mode 100644 index 00000000..38ce0bcc --- /dev/null +++ b/mission/controller/acs/util/CholeskyDecomposition.h @@ -0,0 +1,102 @@ +/* + * TinyEKF: Extended Kalman Filter for embedded processors + * + * Copyright (C) 2015 Simon D. Levy + * + * MIT License + */ +#ifndef CHOLESKYDECOMPOSITION_H_ +#define CHOLESKYDECOMPOSITION_H_ +#include +//typedef unsigned int uint8_t; + +template +class CholeskyDecomposition { +public: + static int invertCholesky(T1 *matrix, T2 *result, T3 *tempMatrix, const uint8_t dimension) + { + // https://github.com/simondlevy/TinyEKF/blob/master/tiny_ekf.c + return cholsl(matrix, result, tempMatrix, dimension); + } +private: + // https://github.com/simondlevy/TinyEKF/blob/master/tiny_ekf.c + static uint8_t choldc1(double * a, double * p, uint8_t n) { + int8_t i,j,k; + double sum; + + for (i = 0; i < n; i++) { + for (j = i; j < n; j++) { + sum = a[i*n+j]; + for (k = i - 1; k >= 0; k--) { + sum -= a[i*n+k] * a[j*n+k]; + } + if (i == j) { + if (sum <= 0) { + return 1; /* error */ + } + p[i] = sqrt(sum); + } + else { + a[j*n+i] = sum / p[i]; + } + } + } + + return 0; /* success */ + } + + // https://github.com/simondlevy/TinyEKF/blob/master/tiny_ekf.c + static uint8_t choldcsl(double * A, double * a, double * p, uint8_t n) + { + uint8_t i,j,k; double sum; + for (i = 0; i < n; i++) + for (j = 0; j < n; j++) + a[i*n+j] = A[i*n+j]; + if (choldc1(a, p, n)) return 1; + for (i = 0; i < n; i++) { + a[i*n+i] = 1 / p[i]; + for (j = i + 1; j < n; j++) { + sum = 0; + for (k = i; k < j; k++) { + sum -= a[j*n+k] * a[k*n+i]; + } + a[j*n+i] = sum / p[j]; + } + } + + return 0; /* success */ + } + + + // https://github.com/simondlevy/TinyEKF/blob/master/tiny_ekf.c + static uint8_t cholsl(double * A,double * a,double * p, uint8_t n) + { + uint8_t i,j,k; + if (choldcsl(A,a,p,n)) return 1; + for (i = 0; i < n; i++) { + for (j = i + 1; j < n; j++) { + a[i*n+j] = 0.0; + } + } + for (i = 0; i < n; i++) { + a[i*n+i] *= a[i*n+i]; + for (k = i + 1; k < n; k++) { + a[i*n+i] += a[k*n+i] * a[k*n+i]; + } + for (j = i + 1; j < n; j++) { + for (k = j; k < n; k++) { + a[i*n+j] += a[k*n+i] * a[k*n+j]; + } + } + } + for (i = 0; i < n; i++) { + for (j = 0; j < i; j++) { + a[i*n+j] = a[j*n+i]; + } + } + + return 0; /* success */ + } +}; + +#endif /* CONTRIB_MATH_CHOLESKYDECOMPOSITION_H_ */ -- 2.34.1 From 338c8299e2ea85ee3d30717d91c2cf2a702fc254 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 19 Sep 2022 15:03:25 +0200 Subject: [PATCH 008/101] added Commanding as ActuatorCmd --- mission/controller/acs/ActuatorCmd.cpp | 83 ++++++++++++++++++++++++++ mission/controller/acs/ActuatorCmd.h | 48 +++++++++++++++ 2 files changed, 131 insertions(+) create mode 100644 mission/controller/acs/ActuatorCmd.cpp create mode 100644 mission/controller/acs/ActuatorCmd.h diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp new file mode 100644 index 00000000..25eeca9c --- /dev/null +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -0,0 +1,83 @@ +/* + * ActuatorCmd.cpp + * + * Created on: 4 Aug 2022 + * Author: Robin Marquardt + */ + + +#include "ActuatorCmd.h" +#include +#include +#include +#include +#include +#include +#include + +ActuatorCmd::ActuatorCmd(AcsParameters *acsParameters_) { + acsParameters = *acsParameters_; +} + +ActuatorCmd::~ActuatorCmd(){ + +} + +void ActuatorCmd::cmdSpeedToRws(const double *speedRw0, const double *speedRw1, const double *speedRw2, + const double *speedRw3, const double *rwTrqIn, const double *rwTrqNS, double *rwCmdSpeed){ + + using namespace Math; + // Scaling the commanded torque to a maximum value + double torque[4] = {0, 0, 0, 0}; + double maxTrq = acsParameters.rwHandlingParameters.maxTrq; + VectorOperations::add(rwTrqIn, rwTrqNS, torque, 4); + + double maxValue = 0; + for (int i = 0; i < 4; i++) { //size of torque, always 4 ? + if (abs(torque[i]) > maxValue) { + maxValue = abs(torque[i]); + } + } + + if (maxValue > maxTrq) { + + double scalingFactor = maxTrq / maxValue; + VectorOperations::mulScalar(torque, scalingFactor, torque, 4); + + } + + // Calculating the commanded speed in RPM for every reaction wheel + double 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; + VectorOperations::mulScalar(torque, factor, deltaSpeed, 4); + VectorOperations::add(speedRws, deltaSpeed, rwCmdSpeed, 4); + + + +} + +void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, double *dipolMomentUnits) { + +// Convert to Unit frame + MatrixOperations::multiply(*acsParameters.magnetorquesParameter.inverseAlignment, dipolMoment, dipolMomentUnits, 3, 3, 1); +// Scaling along largest element if dipol exceeds maximum + double maxDipol = acsParameters.magnetorquesParameter.DipolMax; + double maxValue = 0; + for (int i = 0; i < 3; i++) { + if (abs(dipolMomentUnits[i]) > maxDipol) { + maxValue = abs(dipolMomentUnits[i]); + } + } + + if (maxValue > maxDipol) { + + double scalingFactor = maxDipol / maxValue; + VectorOperations::mulScalar(dipolMomentUnits, scalingFactor, dipolMomentUnits, 3); + + } +} diff --git a/mission/controller/acs/ActuatorCmd.h b/mission/controller/acs/ActuatorCmd.h new file mode 100644 index 00000000..9b721505 --- /dev/null +++ b/mission/controller/acs/ActuatorCmd.h @@ -0,0 +1,48 @@ +/* + * ActuatorCmd.h + * + * Created on: 4 Aug 2022 + * Author: Robin Marquardt + */ + +#ifndef ACTUATORCMD_H_ +#define ACTUATORCMD_H_ + + +#include "AcsParameters.h" +#include "SensorProcessing.h" +#include +#include +#include + +class ActuatorCmd{ +public: + ActuatorCmd(AcsParameters *acsParameters_); //Input mode ? + virtual ~ActuatorCmd(); + + /* + * @brief: cmdSpeedToRws() will set the maximum possible torque for the reaction wheels, also + * will calculate the needed revolutions per minute for the RWs, which will be given + * as Input to the RWs + * @param: rwTrqIn given torque from pointing controller + * rwTrqNS Nullspace torque + * rwCmdSpeed output revolutions per minute for every reaction wheel + */ + void cmdSpeedToRws(const double *speedRw0, const double *speedRw1, const double *speedRw2, const double *speedRw3, + const double *rwTrqIn, const double *rwTrqNS, double *rwCmdSpeed); + + /* + * @brief: cmdDipolMtq() gives the commanded dipol moment for the magnetorques + * + * @param: dipolMoment given dipol moment in spacecraft frame + * dipolMomentUnits resulting dipol moment for every unit + */ + void cmdDipolMtq(const double *dipolMoment, double *dipolMomentUnits); + +protected: + +private: + AcsParameters acsParameters; +}; + +#endif /* ACTUATORCMD_H_ */ -- 2.34.1 From 053c1a7fe8f7385370eedd894b1ef1d2f399d359 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 19 Sep 2022 15:17:39 +0200 Subject: [PATCH 009/101] added Guidance --- mission/controller/acs/Guidance.cpp | 347 ++++++++++++++++++++++++++++ mission/controller/acs/Guidance.h | 42 ++++ 2 files changed, 389 insertions(+) create mode 100644 mission/controller/acs/Guidance.cpp create mode 100644 mission/controller/acs/Guidance.h diff --git a/mission/controller/acs/Guidance.cpp b/mission/controller/acs/Guidance.cpp new file mode 100644 index 00000000..d861769d --- /dev/null +++ b/mission/controller/acs/Guidance.cpp @@ -0,0 +1,347 @@ +/* + * Guidance.cpp + * + * Created on: 6 Jun 2022 + * Author: Robin Marquardt + */ + + +#include "Guidance.h" +#include "string.h" +#include +#include +#include +#include +#include +#include + +Guidance::Guidance(AcsParameters *acsParameters_) { + acsParameters = *acsParameters_; + +} + +Guidance::~Guidance() { + +} + +void Guidance::getTargetParamsSafe(double sunTargetSafe[3], double satRateSafe[3]) { + + for (int i = 0; i < 3; i++) { + + sunTargetSafe[i] = + acsParameters.safeModeControllerParameters.sunTargetDir[i]; + satRateSafe[i] = + acsParameters.safeModeControllerParameters.satRateRef[i]; + + } + + +// memcpy(sunTargetSafe, acsParameters.safeModeControllerParameters.sunTargetDir, 24); + +} + +void Guidance::targetQuatPtg(ACS::SensorValues* sensorValues, ACS::OutputValues *outputValues, + timeval now, double targetQuat[4], double refSatRate[3]){ +//------------------------------------------------------------------------------------- +// Calculation of target quaternion to groundstation +//------------------------------------------------------------------------------------- +// Transform longitude, latitude and altitude of groundstation to cartesian coordiantes (earth fixed/centered frame) + double groundStationCart[3] = {0, 0, 0}; + + MathOperations::cartesianFromLatLongAlt(acsParameters.groundStationParameters.latitudeGs, + acsParameters.groundStationParameters.longitudeGs, acsParameters.groundStationParameters.altitudeGs, + groundStationCart); + +// Position of the satellite in the earth/fixed frame via GPS + double posSatE[3] = {0, 0, 0}; + MathOperations::cartesianFromLatLongAlt(sensorValues->gps0latitude, sensorValues->gps0longitude, + sensorValues->gps0altitude, posSatE); + +// Target direction in the ECEF frame + double targetDirE[3] = {0, 0, 0}; + VectorOperations::subtract(groundStationCart, posSatE, targetDirE, 3); + +// Transformation between ECEF and IJK frame + double dcmEJ[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double dcmJE[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MathOperations::dcmEJ(now, *dcmEJ); + MathOperations::inverseMatrixDimThree(*dcmEJ, *dcmJE); +// Derivative of dmcEJ WITHOUT PRECISSION AND NUTATION + double dcmEJDot[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double dcmJEDot[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double dcmDot[3][3] = {{0, 1, 0}, {-1, 0, 0}, {0, 0, 0}}; + double omegaEarth = acsParameters.targetModeControllerParameters.omegaEarth; + +// TEST SECTION ! + double dcmTEST[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MatrixOperations::multiply(&acsParameters.magnetorquesParameter.mtq0orientationMatrix, dcmTEST, dcmTEST, 3, 3, 3); + + MatrixOperations::multiply(*dcmDot, *dcmEJ, *dcmEJDot, 3, 3, 3); + MatrixOperations::multiplyScalar(*dcmEJDot, omegaEarth, *dcmEJDot, 3, 3); + MathOperations::inverseMatrixDimThree(*dcmEJDot, *dcmJEDot); + +// Transformation between ECEF and Body frame + double dcmBJ[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double dcmBE[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double quatBJ[4] = {0, 0, 0, 0}; + quatBJ[0] = outputValues->quatMekfBJ[0]; + quatBJ[1] = outputValues->quatMekfBJ[1]; + quatBJ[2] = outputValues->quatMekfBJ[2]; + quatBJ[3] = outputValues->quatMekfBJ[3]; + QuaternionOperations::toDcm(quatBJ, dcmBJ); + MatrixOperations::multiply(*dcmBJ, *dcmJE, *dcmBE, 3, 3, 3); + +// Target Direction in the body frame + double targetDirB[3] = {0, 0, 0}; + MatrixOperations::multiply(*dcmBE, targetDirE, targetDirB, 3, 3, 1); + +// 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]; + double noramlizedTargetDirB[3] = {0, 0, 0}; + VectorOperations::normalize(targetDirB, noramlizedTargetDirB, 3); + VectorOperations::normalize(refDir, refDir, 3); + double normTargetDirB = VectorOperations::norm(noramlizedTargetDirB, 3); + double normRefDir = VectorOperations::norm(refDir, 3); + double crossDir[3] = {0, 0, 0}; + double dotDirections = VectorOperations::dot(noramlizedTargetDirB, refDir); + VectorOperations::cross(noramlizedTargetDirB, refDir, crossDir); + targetQuat[0] = crossDir[0]; + targetQuat[1] = crossDir[1]; + targetQuat[2] = crossDir[2]; + targetQuat[3] = sqrt(pow(normTargetDirB,2) * pow(normRefDir,2) + dotDirections); + VectorOperations::normalize(targetQuat, targetQuat, 4); + +//------------------------------------------------------------------------------------- +// Calculation of reference rotation rate +//------------------------------------------------------------------------------------- + double velSatE[3] = {0, 0, 0}; + velSatE[0] = sensorValues->gps0Velocity[0]; + velSatE[1] = sensorValues->gps0Velocity[1]; + velSatE[2] = sensorValues->gps0Velocity[2]; + double velSatB[3] = {0, 0, 0}, velSatBPart1[3] = {0, 0, 0}, + velSatBPart2[3] = {0, 0, 0}; +// Velocity: v_B = dcm_BI * dcmIE * v_E + dcm_BI * DotDcm_IE * v_E + MatrixOperations::multiply(*dcmBE, velSatE, velSatBPart1, 3, 3, 1); + double dcmBEDot[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MatrixOperations::multiply(*dcmBJ, *dcmJEDot, *dcmBEDot, 3, 3, 3); + MatrixOperations::multiply(*dcmBEDot, posSatE, velSatBPart2, 3, 3, 1); + VectorOperations::add(velSatBPart1, velSatBPart2, velSatB, 3); + + double normVelSatB = VectorOperations::norm(velSatB, 3); + double normRefSatRate = normVelSatB / normTargetDirB; + + double satRateDir[3] = {0, 0, 0}; + VectorOperations::cross(velSatB, targetDirB, satRateDir); + VectorOperations::normalize(satRateDir, satRateDir, 3); + VectorOperations::mulScalar(satRateDir, normRefSatRate, refSatRate, 3); + +//------------------------------------------------------------------------------------- +// Calculation of reference rotation rate in case of star tracker blinding +//------------------------------------------------------------------------------------- + if ( acsParameters.targetModeControllerParameters.avoidBlindStr ) { + + double sunDirJ[3] = {0, 0, 0}; + double sunDirB[3] = {0, 0, 0}; + + if ( outputValues->sunDirModelValid ) { + + sunDirJ[0] = outputValues->sunDirModel[0]; + sunDirJ[1] = outputValues->sunDirModel[1]; + sunDirJ[2] = outputValues->sunDirModel[2]; + MatrixOperations::multiply(*dcmBJ, sunDirJ, sunDirB, 3, 3, 1); + } + + else { + sunDirB[0] = outputValues->sunDirEst[0]; + sunDirB[1] = outputValues->sunDirEst[1]; + sunDirB[2] = outputValues->sunDirEst[2]; + + } + + double exclAngle = acsParameters.strParameters.exclusionAngle, + blindStart = acsParameters.targetModeControllerParameters.blindAvoidStart, + blindEnd = acsParameters.targetModeControllerParameters.blindAvoidStop; + + double sightAngleSun = VectorOperations::dot(acsParameters.strParameters.boresightAxis, sunDirB); + + if ( !(strBlindAvoidFlag) ) { + + double critSightAngle = blindStart * exclAngle; + + if ( sightAngleSun < critSightAngle) { + strBlindAvoidFlag = true; + } + + } + + else { + if ( sightAngleSun < blindEnd * exclAngle) { + + double normBlindRefRate = acsParameters.targetModeControllerParameters.blindRotRate; + double blindRefRate[3] = {0, 0, 0}; + + + if ( sunDirB[1] < 0) { + blindRefRate[0] = normBlindRefRate; + blindRefRate[1] = 0; + blindRefRate[2] = 0; + } + else { + blindRefRate[0] = -normBlindRefRate; + blindRefRate[1] = 0; + blindRefRate[2] = 0; + } + + VectorOperations::add(blindRefRate, refSatRate, refSatRate, 3); + + } + else { + strBlindAvoidFlag = false; + } + } + } +} + + +void Guidance::comparePtg(double targetQuat[4], ACS::OutputValues *outputValues, double refSatRate[3], double quatError[3], double deltaRate[3] ) { + + double quatRef[4] = {0, 0, 0, 0}; + quatRef[0] = acsParameters.targetModeControllerParameters.quatRef[0]; + quatRef[1] = acsParameters.targetModeControllerParameters.quatRef[1]; + quatRef[2] = acsParameters.targetModeControllerParameters.quatRef[2]; + quatRef[3] = acsParameters.targetModeControllerParameters.quatRef[3]; + + double satRate[3] = {0, 0, 0}; + satRate[0] = outputValues->satRateMekf[0]; + satRate[1] = outputValues->satRateMekf[1]; + satRate[2] = outputValues->satRateMekf[2]; + VectorOperations::subtract(satRate, refSatRate, deltaRate, 3); + // valid checks ? + double quatErrorMtx[4][4] = {{ quatRef[3], quatRef[2], -quatRef[1], -quatRef[0] }, + { -quatRef[2], quatRef[3], quatRef[0], -quatRef[1] }, + { quatRef[1], -quatRef[0], quatRef[3], -quatRef[2] }, + { quatRef[0], -quatRef[1], quatRef[2], quatRef[3] }}; + + double quatErrorComplete[4] = {0, 0, 0, 0}; + MatrixOperations::multiply(*quatErrorMtx, targetQuat, quatErrorComplete, 4, 4, 1); + + if (quatErrorComplete[3] < 0) { + quatErrorComplete[3] *= -1; + } + + quatError[0] = quatErrorComplete[0]; + quatError[1] = quatErrorComplete[1]; + quatError[2] = quatErrorComplete[2]; + + // target flag in matlab, importance, does look like it only gives + // feedback if pointing control is under 150 arcsec ?? + +} + + +void Guidance::getDistributionMatrixRw(ACS::SensorValues* sensorValues, double *rwPseudoInv) { + + if (sensorValues->validRw0 && sensorValues->validRw1 && sensorValues->validRw2 && sensorValues->validRw3) { + + rwPseudoInv[0] = acsParameters.rwMatrices.pseudoInverse[0][0]; + rwPseudoInv[1] = acsParameters.rwMatrices.pseudoInverse[0][1]; + rwPseudoInv[2] = acsParameters.rwMatrices.pseudoInverse[0][2]; + rwPseudoInv[3] = acsParameters.rwMatrices.pseudoInverse[1][0]; + rwPseudoInv[4] = acsParameters.rwMatrices.pseudoInverse[1][1]; + rwPseudoInv[5] = acsParameters.rwMatrices.pseudoInverse[1][2]; + rwPseudoInv[6] = acsParameters.rwMatrices.pseudoInverse[2][0]; + rwPseudoInv[7] = acsParameters.rwMatrices.pseudoInverse[2][1]; + rwPseudoInv[8] = acsParameters.rwMatrices.pseudoInverse[2][2]; + rwPseudoInv[9] = acsParameters.rwMatrices.pseudoInverse[3][0]; + rwPseudoInv[10] = acsParameters.rwMatrices.pseudoInverse[3][1]; + rwPseudoInv[11] = acsParameters.rwMatrices.pseudoInverse[3][2]; + + } + + else if (!(sensorValues->validRw0) && sensorValues->validRw1 && sensorValues->validRw2 && sensorValues->validRw3) { + + rwPseudoInv[0] = acsParameters.rwMatrices.without0[0][0]; + rwPseudoInv[1] = acsParameters.rwMatrices.without0[0][1]; + rwPseudoInv[2] = acsParameters.rwMatrices.without0[0][2]; + rwPseudoInv[3] = acsParameters.rwMatrices.without0[1][0]; + rwPseudoInv[4] = acsParameters.rwMatrices.without0[1][1]; + rwPseudoInv[5] = acsParameters.rwMatrices.without0[1][2]; + rwPseudoInv[6] = acsParameters.rwMatrices.without0[2][0]; + rwPseudoInv[7] = acsParameters.rwMatrices.without0[2][1]; + rwPseudoInv[8] = acsParameters.rwMatrices.without0[2][2]; + rwPseudoInv[9] = acsParameters.rwMatrices.without0[3][0]; + rwPseudoInv[10] = acsParameters.rwMatrices.without0[3][1]; + rwPseudoInv[11] = acsParameters.rwMatrices.without0[3][2]; + } + + else if ((sensorValues->validRw0) && !(sensorValues->validRw1) && sensorValues->validRw2 && sensorValues->validRw3) { + + rwPseudoInv[0] = acsParameters.rwMatrices.without1[0][0]; + rwPseudoInv[1] = acsParameters.rwMatrices.without1[0][1]; + rwPseudoInv[2] = acsParameters.rwMatrices.without1[0][2]; + rwPseudoInv[3] = acsParameters.rwMatrices.without1[1][0]; + rwPseudoInv[4] = acsParameters.rwMatrices.without1[1][1]; + rwPseudoInv[5] = acsParameters.rwMatrices.without1[1][2]; + rwPseudoInv[6] = acsParameters.rwMatrices.without1[2][0]; + rwPseudoInv[7] = acsParameters.rwMatrices.without1[2][1]; + rwPseudoInv[8] = acsParameters.rwMatrices.without1[2][2]; + rwPseudoInv[9] = acsParameters.rwMatrices.without1[3][0]; + rwPseudoInv[10] = acsParameters.rwMatrices.without1[3][1]; + rwPseudoInv[11] = acsParameters.rwMatrices.without1[3][2]; + } + + else if ((sensorValues->validRw0) && (sensorValues->validRw1) && !(sensorValues->validRw2) && sensorValues->validRw3) { + + rwPseudoInv[0] = acsParameters.rwMatrices.without2[0][0]; + rwPseudoInv[1] = acsParameters.rwMatrices.without2[0][1]; + rwPseudoInv[2] = acsParameters.rwMatrices.without2[0][2]; + rwPseudoInv[3] = acsParameters.rwMatrices.without2[1][0]; + rwPseudoInv[4] = acsParameters.rwMatrices.without2[1][1]; + rwPseudoInv[5] = acsParameters.rwMatrices.without2[1][2]; + rwPseudoInv[6] = acsParameters.rwMatrices.without2[2][0]; + rwPseudoInv[7] = acsParameters.rwMatrices.without2[2][1]; + rwPseudoInv[8] = acsParameters.rwMatrices.without2[2][2]; + rwPseudoInv[9] = acsParameters.rwMatrices.without2[3][0]; + rwPseudoInv[10] = acsParameters.rwMatrices.without2[3][1]; + rwPseudoInv[11] = acsParameters.rwMatrices.without2[3][2]; + } + + else if ((sensorValues->validRw0) && (sensorValues->validRw1) && (sensorValues->validRw2) && (sensorValues->validRw3)) { + + rwPseudoInv[0] = acsParameters.rwMatrices.without3[0][0]; + rwPseudoInv[1] = acsParameters.rwMatrices.without3[0][1]; + rwPseudoInv[2] = acsParameters.rwMatrices.without3[0][2]; + rwPseudoInv[3] = acsParameters.rwMatrices.without3[1][0]; + rwPseudoInv[4] = acsParameters.rwMatrices.without3[1][1]; + rwPseudoInv[5] = acsParameters.rwMatrices.without3[1][2]; + rwPseudoInv[6] = acsParameters.rwMatrices.without3[2][0]; + rwPseudoInv[7] = acsParameters.rwMatrices.without3[2][1]; + rwPseudoInv[8] = acsParameters.rwMatrices.without3[2][2]; + rwPseudoInv[9] = acsParameters.rwMatrices.without3[3][0]; + rwPseudoInv[10] = acsParameters.rwMatrices.without3[3][1]; + rwPseudoInv[11] = acsParameters.rwMatrices.without3[3][2]; + } + + else { +// @note: This one takes the normal pseudoInverse of all four raction wheels valid. +// Does not make sense, but is implemented that way in MATLAB ?! +// Thought: It does not really play a role, because in case there are more then one +// reaction wheel the pointing control is destined to fail. + rwPseudoInv[0] = acsParameters.rwMatrices.pseudoInverse[0][0]; + rwPseudoInv[1] = acsParameters.rwMatrices.pseudoInverse[0][1]; + rwPseudoInv[2] = acsParameters.rwMatrices.pseudoInverse[0][2]; + rwPseudoInv[3] = acsParameters.rwMatrices.pseudoInverse[1][0]; + rwPseudoInv[4] = acsParameters.rwMatrices.pseudoInverse[1][1]; + rwPseudoInv[5] = acsParameters.rwMatrices.pseudoInverse[1][2]; + rwPseudoInv[6] = acsParameters.rwMatrices.pseudoInverse[2][0]; + rwPseudoInv[7] = acsParameters.rwMatrices.pseudoInverse[2][1]; + rwPseudoInv[8] = acsParameters.rwMatrices.pseudoInverse[2][2]; + rwPseudoInv[9] = acsParameters.rwMatrices.pseudoInverse[3][0]; + rwPseudoInv[10] = acsParameters.rwMatrices.pseudoInverse[3][1]; + rwPseudoInv[11] = acsParameters.rwMatrices.pseudoInverse[3][2]; + + } +} diff --git a/mission/controller/acs/Guidance.h b/mission/controller/acs/Guidance.h new file mode 100644 index 00000000..736d8b9b --- /dev/null +++ b/mission/controller/acs/Guidance.h @@ -0,0 +1,42 @@ +/* + * Guidance.h + * + * Created on: 6 Jun 2022 + * Author: Robin Marquardt + */ + +#ifndef GUIDANCE_H_ +#define GUIDANCE_H_ + + +#include +#include +#include +#include + + +class Guidance { +public: + Guidance(AcsParameters *acsParameters_); + virtual ~Guidance(); + + void getTargetParamsSafe(double sunTargetSafe[3], double satRateRef[3]); + + // Function to get the target quaternion and refence rotation rate from gps position and position of the ground station + void targetQuatPtg(ACS::SensorValues* sensorValues, ACS::OutputValues *outputValues, timeval now, + double targetQuat[4], double refSatRate[3]); + + // @note: compares target Quaternion and reference quaternion, also actual satellite rate and desired + void comparePtg( double targetQuat[4], ACS::OutputValues *outputValues, double refSatRate[3], double quatError[3], double deltaRate[3] ); + +// @note: will give back the pseudoinverse matrix for the reaction wheel depending on the valid reation wheel +// maybe can be done in "commanding.h" + void getDistributionMatrixRw(ACS::SensorValues* sensorValues, double *rwPseudoInv); + + +private: + AcsParameters acsParameters; + bool strBlindAvoidFlag = false; +}; + +#endif /* ACS_GUIDANCE_H_ */ -- 2.34.1 From 84b0856b52ee4480ca58e22875175100640487fc Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 19 Sep 2022 15:26:51 +0200 Subject: [PATCH 010/101] added OutputValues --- mission/controller/acs/OutputValues.cpp | 19 +++++++++ mission/controller/acs/OutputValues.h | 51 +++++++++++++++++++++++++ 2 files changed, 70 insertions(+) create mode 100644 mission/controller/acs/OutputValues.cpp create mode 100644 mission/controller/acs/OutputValues.h diff --git a/mission/controller/acs/OutputValues.cpp b/mission/controller/acs/OutputValues.cpp new file mode 100644 index 00000000..3deb4043 --- /dev/null +++ b/mission/controller/acs/OutputValues.cpp @@ -0,0 +1,19 @@ +/* + * OutputValues.cpp + * + * Created on: 30 Mar 2022 + * Author: rooob + */ +#include + +namespace ACS { + +OutputValues::OutputValues(){ + +} + +OutputValues::~OutputValues(){ + +} + +} diff --git a/mission/controller/acs/OutputValues.h b/mission/controller/acs/OutputValues.h new file mode 100644 index 00000000..a73dc43c --- /dev/null +++ b/mission/controller/acs/OutputValues.h @@ -0,0 +1,51 @@ +/* + * OutputValues.h + * + * Created on: 30 Mar 2022 + * Author: rooob + */ + +#ifndef OUTPUTVALUES_H_ +#define OUTPUTVALUES_H_ + + +namespace ACS { + +class OutputValues { + +public: + + OutputValues(); + virtual ~OutputValues(); + + double magFieldEst[3]; // sensor fusion (G) + bool magFieldEstValid; + double magFieldModel[3]; //igrf (IJK) + bool magFieldModelValid; + double magneticFieldVectorDerivative[3]; + bool magneticFieldVectorDerivativeValid; + + bool mgmUpdated; + + double sunDirEst[3]; // sensor fusion (G) + bool sunDirEstValid; + double sunDirModel[3]; //sun model (IJK) + bool sunDirModelValid; + + double quatMekfBJ[4]; //mekf + bool quatMekfBJValid; + + double satRateEst[3]; + bool satRateEstValid; + double satRateMekf[3]; // after mekf with correction of bias + bool satRateMekfValid; + double sunVectorDerivative[3]; + bool sunVectorDerivativeValid; + + double gcLatitude; // geocentric latitude, radian + double gdLongitude; // Radian longitude +}; +} + + +#endif OUTPUTVALUES_H_ -- 2.34.1 From 295a2e3fdc2dab0066c9d12477b677bc72f5fc22 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 19 Sep 2022 15:37:05 +0200 Subject: [PATCH 011/101] added SensorValues --- mission/controller/acs/SensorValues.cpp | 35 +++++++++ mission/controller/acs/SensorValues.h | 99 +++++++++++++++++++++++++ 2 files changed, 134 insertions(+) create mode 100644 mission/controller/acs/SensorValues.cpp create mode 100644 mission/controller/acs/SensorValues.h diff --git a/mission/controller/acs/SensorValues.cpp b/mission/controller/acs/SensorValues.cpp new file mode 100644 index 00000000..f3a52dea --- /dev/null +++ b/mission/controller/acs/SensorValues.cpp @@ -0,0 +1,35 @@ +/* + * SensorValues.cpp + * + * Created on: 30 Mar 2022 + * Author: rooob + */ +#include + +#include +#include +#include + +namespace ACS { + +SensorValues::SensorValues() { +} + +SensorValues::~SensorValues() { +} + +ReturnValue_t SensorValues::update() { +// lp_var_t quaternion(objects::STAR_TRACKER, PoolIds::CALI_QW, nullptr, pool_rwm_t::VAR_READ); +// ReturnValue_t result = quaternion.read(); + +// if ( result != RETURN_OK) { +// return RETURN_FAILED; +// } +// quatJB[3] = static_cast(quaternion.value); +// quatJBValid = quaternion.isValid(); + + return RETURN_OK; +} +} + + diff --git a/mission/controller/acs/SensorValues.h b/mission/controller/acs/SensorValues.h new file mode 100644 index 00000000..1a328e16 --- /dev/null +++ b/mission/controller/acs/SensorValues.h @@ -0,0 +1,99 @@ +/* Created on: 08.03.2022 + * Author: Robin + */ + +#ifndef SENSORVALUES_H_ +#define SENSORVALUES_H_ + +#include + +namespace ACS { + +class SensorValues: public HasReturnvaluesIF { +public: + SensorValues(); + virtual ~SensorValues(); + + ReturnValue_t update(); + + float mgm0[3]; + float mgm1[3]; + float mgm2[3]; + float mgm3[3]; + float mgm4[3]; + + bool mgm0Valid; + bool mgm1Valid; + bool mgm2Valid; + bool mgm3Valid; + bool mgm4Valid; + + float sus0[3]; + float sus1[3]; + float sus2[3]; + float sus3[3]; + float sus4[3]; + float sus5[3]; + float sus6[3]; + float sus7[3]; + float sus8[3]; + float sus9[3]; + float sus10[3]; + float sus11[3]; + + bool sus0Valid; + bool sus1Valid; + bool sus2Valid; + bool sus3Valid; + bool sus4Valid; + bool sus5Valid; + bool sus6Valid; + bool sus7Valid; + bool sus8Valid; + bool sus9Valid; + bool sus10Valid; + bool sus11Valid; + + + double rmu0[3]; + double rmu1[3]; + double rmu2[3]; + + bool rmu0Valid; + bool rmu1Valid; + bool rmu2Valid; + + double quatJB[4]; // output star tracker. quaternion or dcm ? refrence to which KOS? + bool quatJBValid; + int strIntTime[2]; + + double gps0latitude; //Reference is WGS84, so this one will probably be geodetic + double gps0longitude; //Should be geocentric for IGRF + double gps0altitude; + double gps0Velocity[3]; // speed over ground = ?? + double gps0Time; //utc + +// valid ids for gps values ! + int gps0TimeYear; + int gps0TimeMonth; + int gps0TimeHour; // should be double + bool gps0Valid; + + + bool mgt0valid; + +// Reaction wheel measurements + double speedRw0; // RPM [1/min] + double speedRw1; // RPM [1/min] + double speedRw2; // RPM [1/min] + double speedRw3; // RPM [1/min] + bool validRw0; + bool validRw1; + bool validRw2; + bool validRw3; + +}; +} /* namespace ACS */ + +#endif ENSORVALUES_H_ + -- 2.34.1 From 28dfcbf0ef4e41a74acc823d3b60062baaa87e7c Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 19 Sep 2022 15:44:14 +0200 Subject: [PATCH 012/101] added SensorProcessing --- mission/controller/acs/SensorProcessing.cpp | 387 ++++++++++++++++++++ mission/controller/acs/SensorProcessing.h | 89 +++++ 2 files changed, 476 insertions(+) create mode 100644 mission/controller/acs/SensorProcessing.cpp create mode 100644 mission/controller/acs/SensorProcessing.h diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp new file mode 100644 index 00000000..eeb7f457 --- /dev/null +++ b/mission/controller/acs/SensorProcessing.cpp @@ -0,0 +1,387 @@ +/* + * SensorProcessing.cpp + * + * Created on: 7 Mar 2022 + * Author: Robin Marquardt + */ + +#include "SensorProcessing.h" +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace Math; +// Thought: Maybe separate file for transforming of sensor values +// into geometry frame and body frame + +SensorProcessing::SensorProcessing(AcsParameters *acsParameters_) : + savedMagFieldEst { 0, 0, 0 }{ + validMagField = false; + validGcLatitude = false; +} + +SensorProcessing::~SensorProcessing() { +} + +bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, + const float *mgm1Value, bool mgm1valid, const float *mgm2Value, + bool mgm2valid, const float *mgm3Value, bool mgm3valid, + const float *mgm4Value, bool mgm4valid, timeval timeOfMgmMeasurement, + const AcsParameters::MgmHandlingParameters *mgmParameters, + const double gpsLatitude, const double gpsLongitude, + const double gpsAltitude, bool gpsValid, double *magFieldEst, bool *outputValid, + double *magFieldModel, bool*magFieldModelValid, + double *magneticFieldVectorDerivative, bool *magneticFieldVectorDerivativeValid) { + + if (!mgm0valid && !mgm1valid && !mgm2valid && !mgm3valid && !mgm4valid) { + *outputValid = false; + validMagField = false; + return false; + } + // Transforming Values to the Body Frame (actually it is the geometry frame atm) + float mgm0ValueBody[3] = {0,0,0}, mgm1ValueBody[3] = {0,0,0}, + mgm2ValueBody[3] = {0,0,0}, mgm3ValueBody[3] = {0,0,0}, + mgm4ValueBody[3] = {0,0,0}; + + bool validUnit[5] = {false, false, false, false, false}; + uint8_t validCount = 0; + if (mgm0valid) { + MatrixOperations::multiply(mgmParameters->mgm0orientationMatrix[0], mgm0Value, mgm0ValueBody, 3, 3, 1); + validCount += 1; + validUnit[0] = true; + } + if (mgm1valid) { + MatrixOperations::multiply(mgmParameters->mgm1orientationMatrix[0], mgm1Value, mgm1ValueBody, 3, 3, 1); + validCount += 1; + validUnit[1] = true; + } + if (mgm2valid) { + MatrixOperations::multiply(mgmParameters->mgm2orientationMatrix[0], mgm2Value, mgm2ValueBody, 3, 3, 1); + validCount += 1; + validUnit[2] = true; + } + if (mgm3valid) { + MatrixOperations::multiply(mgmParameters->mgm3orientationMatrix[0], mgm3Value, mgm3ValueBody, 3, 3, 1); + validCount += 1; + validUnit[3] = true; + } + if (mgm4valid) { + MatrixOperations::multiply(mgmParameters->mgm4orientationMatrix[0], mgm4Value, mgm4ValueBody, 3, 3, 1); + validCount += 1; + validUnit[4] = true; + } + + /* -------- MagFieldEst: Middle Value ------- */ + float mgmValues[3][5] = { { mgm0ValueBody[0], mgm1ValueBody[0], mgm2ValueBody[0], + mgm3ValueBody[0], mgm4ValueBody[0] }, { mgm0ValueBody[1], mgm1ValueBody[1], + mgm2ValueBody[1], mgm3ValueBody[1], mgm4ValueBody[1] }, { mgm0ValueBody[2], + mgm1ValueBody[2], mgm2ValueBody[2], mgm3ValueBody[2], mgm4ValueBody[2] } }; + double mgmValidValues[3][validCount]; + uint8_t j = 0; + for (uint8_t i = 0; i < validCount; i++) { + if (validUnit[i]) { + mgmValidValues[0][j] = mgmValues[0][i]; + mgmValidValues[1][j] = mgmValues[1][i]; + mgmValidValues[2][j] = mgmValues[2][i]; + j += 1; + } + } + //Selection Sort + double mgmValidValuesSort[3][validCount]; + MathOperations::selectionSort(*mgmValidValues, *mgmValidValuesSort, 3, validCount); + + uint8_t n = ceil(validCount/2); + magFieldEst[0] = mgmValidValuesSort[0][n]; + magFieldEst[1] = mgmValidValuesSort[1][n]; + magFieldEst[2] = mgmValidValuesSort[2][n]; + validMagField = true; + + //-----------------------Mag Rate Computation --------------------------------------------------- + double timeDiff = timevalOperations::toDouble(timeOfMgmMeasurement - timeOfSavedMagFieldEst); + for (uint8_t i = 0; i < 3; i++) { + magneticFieldVectorDerivative[i] = (magFieldEst[i] + - savedMagFieldEst[i]) / timeDiff; + savedMagFieldEst[i] = magFieldEst[i]; + } + + *magneticFieldVectorDerivativeValid = true; + if (timeOfSavedMagFieldEst.tv_sec == 0) { + magneticFieldVectorDerivative[0] = 0; + magneticFieldVectorDerivative[1] = 0; + magneticFieldVectorDerivative[2] = 0; + *magneticFieldVectorDerivativeValid = false; + } + + timeOfSavedMagFieldEst = timeOfMgmMeasurement; + + + *outputValid = true; + + // ---------------- IGRF- 13 Implementation here ------------------------------------------------ + if (!gpsValid){ + *magFieldModelValid = false; + } + else{ + // Should be existing class object which will be called and modified here. + Igrf13Model igrf13; + // So the line above should not be done here. Update: Can be done here as long updated coffs +// stored in acsParameters ? + igrf13.updateCoeffGH(timeOfMgmMeasurement); + // maybe put a condition here, to only update after a full day, this + // class function has around 700 steps to perform + igrf13.magFieldComp(gpsLongitude, gpsLatitude, gpsAltitude, + timeOfMgmMeasurement, magFieldModel); + *magFieldModelValid = false; + } + + return true; +} + +void SensorProcessing::processSus(const float sus0Value[], bool sus0valid, const float sus1Value[], bool sus1valid, + const float sus2Value[], bool sus2valid, const float sus3Value[], bool sus3valid, + const float sus4Value[], bool sus4valid, const float sus5Value[], bool sus5valid, + const float sus6Value[], bool sus6valid, const float sus7Value[], bool sus7valid, + const float sus8Value[], bool sus8valid, const float sus9Value[], bool sus9valid, + const float sus10Value[], bool sus10valid, const float sus11Value[], bool sus11valid, + timeval timeOfSusMeasurement, const AcsParameters::SusHandlingParameters *susParameters, + const AcsParameters::SunModelParameters *sunModelParameters, double *sunDirEst, bool *sunDirEstValid, + double *sunVectorInertial, bool *sunVectorInertialValid, + double *sunVectorDerivative, bool *sunVectorDerivativeValid){ + + if(!sus0valid && !sus1valid && !sus2valid && !sus3valid && !sus4valid && !sus5valid + && !sus6valid && !sus7valid && !sus8valid && !sus9valid && !sus10valid && !sus11valid){ + *sunDirEstValid = false; + return; + } + else{ + // WARNING: NOT TRANSFORMED IN BODY FRAME YET + // Transformation into Geomtry Frame + float sus0ValueBody[3] = {0,0,0}, sus1ValueBody[3] = {0,0,0}, sus2ValueBody[3] = {0,0,0}, + sus3ValueBody[3] = {0,0,0}, sus4ValueBody[3] = {0,0,0}, sus5ValueBody[3] = {0,0,0}, + sus6ValueBody[3] = {0,0,0}, sus7ValueBody[3] = {0,0,0}, sus8ValueBody[3] = {0,0,0}, + sus9ValueBody[3] = {0,0,0}, sus10ValueBody[3] = {0,0,0}, sus11ValueBody[3] = {0,0,0}; + + if (sus0valid) { + MatrixOperations::multiply(susParameters->sus0orientationMatrix[0], sus0Value, sus0ValueBody, 3, 3, 1); + } + if (sus1valid) { + MatrixOperations::multiply(susParameters->sus1orientationMatrix[0], sus1Value, sus1ValueBody, 3, 3, 1); + } + if (sus2valid) { + MatrixOperations::multiply(susParameters->sus2orientationMatrix[0], sus2Value, sus2ValueBody, 3, 3, 1); + } + if (sus3valid) { + MatrixOperations::multiply(susParameters->sus3orientationMatrix[0], sus3Value, sus3ValueBody, 3, 3, 1); + } + if (sus4valid) { + MatrixOperations::multiply(susParameters->sus4orientationMatrix[0], sus4Value, sus4ValueBody, 3, 3, 1); + } + if (sus5valid) { + MatrixOperations::multiply(susParameters->sus5orientationMatrix[0], sus5Value, sus5ValueBody, 3, 3, 1); + } + if (sus6valid) { + MatrixOperations::multiply(susParameters->sus6orientationMatrix[0], sus6Value, sus6ValueBody, 3, 3, 1); + } + if (sus7valid) { + MatrixOperations::multiply(susParameters->sus7orientationMatrix[0], sus7Value, sus7ValueBody, 3, 3, 1); + } + if (sus8valid) { + MatrixOperations::multiply(susParameters->sus8orientationMatrix[0], sus8Value, sus8ValueBody, 3, 3, 1); + } + if (sus9valid) { + MatrixOperations::multiply(susParameters->sus9orientationMatrix[0], sus9Value, sus9ValueBody, 3, 3, 1); + } + if (sus10valid) { + MatrixOperations::multiply(susParameters->sus10orientationMatrix[0], sus10Value, sus10ValueBody, 3, 3, 1); + } + if (sus11valid) { + MatrixOperations::multiply(susParameters->sus11orientationMatrix[0], sus11Value, sus11ValueBody, 3, 3, 1); + } + + /* ------ Mean Value: susDirEst ------ */ + // Timo already done + bool validIds[12] = {sus0valid, sus1valid, sus2valid, sus3valid, sus4valid, sus5valid, + sus6valid, sus7valid, sus8valid, sus9valid, sus10valid, sus11valid}; + float susValuesBody[3][12] = {{sus0ValueBody[0], sus1ValueBody[0], sus2ValueBody[0], sus3ValueBody[0], sus4ValueBody[0], + sus5ValueBody[0], sus6ValueBody[0], sus7ValueBody[0], sus8ValueBody[0], sus9ValueBody[0], sus10ValueBody[0], sus11ValueBody[0]}, + {sus0ValueBody[1], sus1ValueBody[1], sus2ValueBody[1], sus3ValueBody[1], sus4ValueBody[1], + sus5ValueBody[1], sus6ValueBody[1], sus7ValueBody[1], sus8ValueBody[1], sus9ValueBody[1], sus10ValueBody[1], sus11ValueBody[1]}, + {sus0ValueBody[2], sus1ValueBody[2], sus2ValueBody[2], sus3ValueBody[2], sus4ValueBody[2], + sus5ValueBody[2], sus6ValueBody[2], sus7ValueBody[2], sus8ValueBody[2], sus9ValueBody[2], sus10ValueBody[2], sus11ValueBody[2]}}; + + double susMeanValue[3] = {0,0,0}; + uint8_t validSusCounter = 0; + for (uint8_t i = 0; i < 12; i++){ + if (validIds[i]){ + susMeanValue[0]+=susValuesBody[0][i]; + susMeanValue[1]+=susValuesBody[1][i]; + susMeanValue[2]+=susValuesBody[2][i]; + validSusCounter+=1; + } + } + double divisor = 1/validSusCounter; + VectorOperations::mulScalar(susMeanValue, divisor, sunDirEst, 3); + *sunDirEstValid = true; + } + + /* -------- Sun Derivatiative --------------------- */ + + double timeDiff = timevalOperations::toDouble(timeOfSusMeasurement - timeOfSavedSusDirEst); + for (uint8_t i = 0; i < 3; i++) { + sunVectorDerivative[i] = (sunDirEst[i] + - savedSunVector[i]) / timeDiff; + savedSunVector[i] = sunDirEst[i]; + } + + *sunVectorDerivativeValid = true; + if (timeOfSavedSusDirEst.tv_sec == 0) { + sunVectorDerivative[0] = 0; + sunVectorDerivative[1] = 0; + sunVectorDerivative[2] = 0; + *sunVectorDerivativeValid = false; + } + + timeOfSavedSusDirEst = timeOfSusMeasurement; + + /* -------- Sun Model Direction (IJK frame) ------- */ + // if (useSunModel) eventuell + double JD2000 = MathOperations::convertUnixToJD2000(timeOfSusMeasurement); + + //Julean Centuries + double JC2000 = JD2000 / 36525; + + double meanLongitude = (sunModelParameters->omega_0 + (sunModelParameters->domega) * JC2000) * PI /180; + double meanAnomaly = (sunModelParameters->m_0 + + sunModelParameters->dm * JC2000) * PI / 180.; + + double eclipticLongitude = meanLongitude + sunModelParameters->p1 * sin(meanAnomaly) + + sunModelParameters->p2 * sin(2 * meanAnomaly); + + double epsilon = sunModelParameters->e - (sunModelParameters->e1) * JC2000; + + + sunVectorInertial[0] = cos(eclipticLongitude); + sunVectorInertial[1] = sin(eclipticLongitude) + * cos(epsilon); + sunVectorInertial[2] = sin(eclipticLongitude) + * sin(epsilon); + + + *sunVectorInertialValid = true; +} + + +void SensorProcessing::processRmu(const double rmu0Value[], bool rmu0valid, + const double rmu1Value[], bool rmu1valid, + const double rmu2Value[], bool rmu2valid, + timeval timeOfrmuMeasurement, const AcsParameters::RmuHandlingParameters *rmuParameters, + double *satRatEst, bool *satRateEstValid){ + + if (!rmu0valid && !rmu1valid && !rmu2valid) { + *satRateEstValid = false; + return; + } + // Transforming Values to the Body Frame (actually it is the geometry frame atm) + double rmu0ValueBody[3] = {0,0,0}, rmu1ValueBody[3]= {0,0,0}, + rmu2ValueBody[3] = {0,0,0}; + + bool validUnit[3] = {false, false, false}; + uint8_t validCount = 0; + if (rmu0valid) { + MatrixOperations::multiply(rmuParameters->rmu0orientationMatrix[0], rmu0Value, rmu0ValueBody, 3, 3, 1); + validCount += 1; + validUnit[0] = true; + } + if (rmu1valid) { + MatrixOperations::multiply(rmuParameters->rmu1orientationMatrix[0], rmu1Value, rmu1ValueBody, 3, 3, 1); + validCount += 1; + validUnit[1] = true; + } + if (rmu2valid) { + MatrixOperations::multiply(rmuParameters->rmu2orientationMatrix[0], rmu2Value, rmu2ValueBody, 3, 3, 1); + validCount += 1; + validUnit[2] = true; + } + + /* -------- SatRateEst: Middle Value ------- */ + double rmuValues[3][3] = { { rmu0ValueBody[0], rmu1ValueBody[0], rmu2ValueBody[0]}, { rmu0ValueBody[1], rmu1ValueBody[1], + rmu2ValueBody[1]}, { rmu0ValueBody[2], + rmu1ValueBody[2], rmu2ValueBody[2]} }; + double rmuValidValues[3][validCount]; + uint8_t j = 0; + for (uint8_t i = 0; i < validCount; i++) { + if (validUnit[i]) { + rmuValidValues[0][j] = rmuValues[0][i]; + rmuValidValues[1][j] = rmuValues[1][i]; + rmuValidValues[2][j] = rmuValues[2][i]; + j += 1; + } + } + //Selection Sort + double rmuValidValuesSort[3][validCount]; + MathOperations::selectionSort(*rmuValidValues, *rmuValidValuesSort, 3, validCount); + + uint8_t n = ceil(validCount/2); + satRatEst[0] = rmuValidValuesSort[0][n]; + satRatEst[1] = rmuValidValuesSort[1][n]; + satRatEst[2] = rmuValidValuesSort[2][n]; + *satRateEstValid = true; + +} + +void SensorProcessing::processGps(const double gps0latitude, const double gps0longitude, + const bool validGps, double *gcLatitude, double *gdLongitude){ + // name to convert not process + if (validGps) { + // Transforming from Degree to Radians and calculation geocentric lattitude from geodetic + *gdLongitude = gps0longitude * PI / 180; + double latitudeRad = gps0latitude * PI / 180; + double eccentricityWgs84 = 0.0818195; + double factor = 1 - pow(eccentricityWgs84, 2); + *gcLatitude = atan(factor * tan(latitudeRad)); + validGcLatitude = true; + + } +} + +void SensorProcessing::process(timeval now, ACS::SensorValues *sensorValues, + ACS::OutputValues *outputValues, const AcsParameters *acsParameters) { + + sensorValues->update(); + processGps(sensorValues->gps0latitude, sensorValues->gps0longitude, + sensorValues->gps0Valid, &outputValues->gcLatitude, &outputValues->gdLongitude); + + outputValues->mgmUpdated = processMgm(sensorValues->mgm0, sensorValues->mgm0Valid, + sensorValues->mgm1, sensorValues->mgm1Valid, + sensorValues->mgm2, sensorValues->mgm2Valid, + sensorValues->mgm3, sensorValues->mgm3Valid, + sensorValues->mgm4, sensorValues->mgm4Valid, now, + &acsParameters->mgmHandlingParameters, outputValues->gcLatitude, + outputValues->gdLongitude, sensorValues->gps0altitude, + sensorValues->gps0Valid, + outputValues->magFieldEst, &outputValues->magFieldEstValid, + outputValues->magFieldModel, &outputValues->magFieldModelValid, + outputValues->magneticFieldVectorDerivative, &outputValues->magneticFieldVectorDerivativeValid); // VALID outputs- PoolVariable ? + + processSus(sensorValues->sus0, sensorValues->sus0Valid, sensorValues->sus1, sensorValues->sus1Valid, + sensorValues->sus2, sensorValues->sus2Valid, sensorValues->sus3, sensorValues->sus3Valid, + sensorValues->sus4, sensorValues->sus4Valid, sensorValues->sus5, sensorValues->sus5Valid, + sensorValues->sus6, sensorValues->sus6Valid, sensorValues->sus7, sensorValues->sus7Valid, + sensorValues->sus8, sensorValues->sus8Valid, sensorValues->sus9, sensorValues->sus9Valid, + sensorValues->sus10, sensorValues->sus10Valid, sensorValues->sus11, sensorValues->sus11Valid, + now, &acsParameters->susHandlingParameters, &acsParameters->sunModelParameters, + outputValues->sunDirEst, &outputValues->sunDirEstValid, + outputValues->sunDirModel, &outputValues->sunDirModelValid, + outputValues->sunVectorDerivative, &outputValues->sunVectorDerivativeValid); // VALID outputs ? + + processRmu(sensorValues->rmu0, sensorValues->rmu0Valid, sensorValues->rmu1, sensorValues->rmu1Valid, + sensorValues->rmu2, sensorValues->rmu2Valid, now, &acsParameters->rmuHandlingParameters, + outputValues->satRateEst, &outputValues->satRateEstValid); + +} + diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h new file mode 100644 index 00000000..9db8e25b --- /dev/null +++ b/mission/controller/acs/SensorProcessing.h @@ -0,0 +1,89 @@ +/******************************* + * EIVE Flight Software Framework (FSFW) + * (c) 2022 IRS, Uni Stuttgart + *******************************/ +#ifndef SENSORPROCESSING_H_ +#define SENSORPROCESSING_H_ + +#include //uint8_t +#include /*purpose, timeval ?*/ +#include "acs/config/classIds.h" +#include +#include "AcsParameters.h" +#include +#include + +/*Planned: + * - Fusion of Sensor Measurements - + * sunDirEst (mean value) + * magField (mean value) + * rmuSatRate (rmus, mean value) + * - Models to get inertia values - + * sunModelDir (input: time) + * magModelField (input: position,time) + * - Low Pass Filter maybe - + * magField + * SunDirEst*/ + +class SensorProcessing: public HasReturnvaluesIF{ +public: + + void reset(); + + SensorProcessing(AcsParameters *acsParameters_); + virtual ~SensorProcessing(); + + void process(timeval now, ACS::SensorValues* sensorValues, ACS::OutputValues *outputValues, + const AcsParameters *acsParameters); // Will call protected functions +private: + +protected: + // short description needed for every function + bool processMgm(const float *mgm0Value, bool mgm0valid, + const float *mgm1Value, bool mgm1valid, + const float *mgm2Value, bool mgm2valid, + const float *mgm3Value, bool mgm3valid, + const float *mgm4Value, bool mgm4valid, + timeval timeOfMgmMeasurement, + const AcsParameters::MgmHandlingParameters *mgmParameters, + const double gpsLatitude, const double gpsLongitude, + const double gpsAltitude, bool gpsValid, + double *magFieldEst, bool *outputValid, + double *magFieldModel, bool*magFieldModelValid, + double *magneticFieldVectorDerivative, bool *magneticFieldVectorDerivativeValid); //Output + + void processSus(const float sus0Value[], bool sus0valid, const float sus1Value[], bool sus1valid, + const float sus2Value[], bool sus2valid, const float sus3Value[], bool sus3valid, + const float sus4Value[], bool sus4valid, const float sus5Value[], bool sus5valid, + const float sus6Value[], bool sus6valid, const float sus7Value[], bool sus7valid, + const float sus8Value[], bool sus8valid, const float sus9Value[], bool sus9valid, + const float sus10Value[], bool sus10valid, const float sus11Value[], bool sus11valid, + timeval timeOfSusMeasurement, const AcsParameters::SusHandlingParameters *susParameters, + const AcsParameters::SunModelParameters *sunModelParameters, double *sunDirEst, bool *sunDirEstValid, + double *sunVectorModel, bool *sunVectorModelValid, + double *sunVectorDerivative, bool *sunVectorDerivativeValid); + + void processRmu(const double rmu0Value[], bool rmu0valid, // processRmu + const double rmu1Value[], bool rmu1valid, + const double rmu2Value[], bool rmu2valid, + timeval timeOfrmuMeasurement, const AcsParameters::RmuHandlingParameters *rmuParameters, + double *satRatEst, bool *satRateEstValid); + + void processStr(); + + void processGps(const double gps0latitude, const double gps0longitude, + const bool validGps, double *gcLatitude, double *gdLongitude); + + + double savedMagFieldEst[3]; + timeval timeOfSavedMagFieldEst; + double savedSunVector[3]; + timeval timeOfSavedSusDirEst; + bool validMagField; + bool validGcLatitude; + + +}; + +#endif SENSORPROCESSING_H_ + -- 2.34.1 From cc82b8aa4223ac038eced821427426db6338a4a9 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 20 Sep 2022 11:20:13 +0200 Subject: [PATCH 013/101] small formatting fixes --- mission/controller/acs/AcsParameters.cpp | 93 ++++++++++++++---------- 1 file changed, 53 insertions(+), 40 deletions(-) diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index 63d8951d..7f5b26c1 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -8,38 +8,46 @@ AcsParameters::AcsParameters() { onBoardParams.sampleTime = 0.1; - inertiaEIVE.inertiaMatrix = {{ 1.0, 0.0, 0.0}, - { 0.0, 1.0, 0.0}, - { 0.0, 0.5, 1.0}}; + inertiaEIVE.inertiaMatrix = { + { 1.0, 0.0, 0.0}, + { 0.0, 1.0, 0.0}, + { 0.0, 0.5, 1.0}}; - mgmHandlingParameters.mgm0orientationMatrix = {{ 0, 0,-1}, - { 0, 1, 0}, - { 1, 0, 0}}; - /*mgmHandlingParameters.mgm1orientationMatrix = {{ 0, 0, 1}, - { 0,-1, 0}, - { 1, 0, 0}}; - mgmHandlingParameters.mgm2orientationMatrix = {{ 0, 0,-1}, - { 0, 1, 0}, - { 1 ,0, 0}}; - mgmHandlingParameters.mgm3orientationMatrix = {{ 0, 0, 1}, - { 0,-1, 0}, - { 1, 0, 0}}; - mgmHandlingParameters.mgm4orientationMatrix = {{ 0, 0,-1}, - {-1, 0, 0}, - { 0, 1, 0}};*/ + mgmHandlingParameters.mgm0orientationMatrix = { + { 0, 0,-1}, + { 0, 1, 0}, + { 1, 0, 0}}; + mgmHandlingParameters.mgm1orientationMatrix = { + { 0, 0, 1}, + { 0,-1, 0}, + { 1, 0, 0}}; + mgmHandlingParameters.mgm2orientationMatrix = { + { 0, 0,-1}, + { 0, 1, 0}, + { 1 ,0, 0}}; + mgmHandlingParameters.mgm3orientationMatrix = { + { 0, 0, 1}, + { 0,-1, 0}, + { 1, 0, 0}}; + mgmHandlingParameters.mgm4orientationMatrix = { + { 0, 0,-1}, + {-1, 0, 0}, + { 0, 1, 0}}; rwHandlingParameters.inertiaWheel = 0.000028198; rwHandlingParameters.maxTrq = 0.0032; //3.2 [mNm] //Geometry frame - rwMatrices.alignmentMatrix = {{ 0.9205, 0.0000, -0.9205, 0.0000}, - { 0.0000, -0.9205, 0.0000, 0.9205}, - { 0.3907, 0.3907, 0.3907, 0.3907}}; + rwMatrices.alignmentMatrix = { + { 0.9205, 0.0000, -0.9205, 0.0000}, + { 0.0000, -0.9205, 0.0000, 0.9205}, + { 0.3907, 0.3907, 0.3907, 0.3907}}; - rwMatrices.pseudoInverse = {{ 0.4434, -0.2845, 0.3597}, - { 0.2136, -0.3317, 1.0123}, - { -0.8672, -0.1406, 0.1778}, - { 0.6426, 0.4794, 1.3603}}; + rwMatrices.pseudoInverse = { + { 0.4434, -0.2845, 0.3597}, + { 0.2136, -0.3317, 1.0123}, + { -0.8672, -0.1406, 0.1778}, + { 0.6426, 0.4794, 1.3603}}; rwMatrices.nullspace = { -0.7358, 0.5469, -0.3637, -0.1649}; @@ -96,21 +104,26 @@ AcsParameters::AcsParameters() { strParameters.boresightAxis = { 0.7593, 0,-0.6508}; strParameters.exclusionAngle = 20 * Math::PI /180; - magnetorquesParameter.mtq0orientationMatrix = {{ 1, 0, 0}, - { 0, 0, 1}, - { 0,-1, 0}}; - magnetorquesParameter.mtq1orientationMatrix = {{ 1, 0, 0}, - { 0, 1, 0}, - { 0, 0, 1}}; - magnetorquesParameter.mtq2orientationMatrix = {{ 0, 0, 1}, - { 0, 1, 0}, - {-1, 0, 0}}; - magnetorquesParameter.alignmentMatrixMtq = {{ 0, 0,-1}, - {-1, 0, 0}, - { 0, 1, 0}}; - magnetorquesParameter.inverseAlignment = {{ 0,-1, 0}, - { 0, 0, 1}, - {-1, 0, 0}}; + magnetorquesParameter.mtq0orientationMatrix = { + { 1, 0, 0}, + { 0, 0, 1}, + { 0,-1, 0}}; + magnetorquesParameter.mtq1orientationMatrix = { + { 1, 0, 0}, + { 0, 1, 0}, + { 0, 0, 1}}; + magnetorquesParameter.mtq2orientationMatrix = { + { 0, 0, 1}, + { 0, 1, 0}, + {-1, 0, 0}}; + magnetorquesParameter.alignmentMatrixMtq = { + { 0, 0,-1}, + {-1, 0, 0}, + { 0, 1, 0}}; + magnetorquesParameter.inverseAlignment = { + { 0,-1, 0}, + { 0, 0, 1}, + {-1, 0, 0}}; magnetorquesParameter.DipolMax = 0.2; } -- 2.34.1 From 3d123a09f3270ead90dd53cf84292198332289a6 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 20 Sep 2022 13:36:17 +0200 Subject: [PATCH 014/101] added control subfolder. added Detumble --- mission/controller/acs/control/Detumble.cpp | 65 +++++++++++++++++++++ mission/controller/acs/control/Detumble.h | 46 +++++++++++++++ 2 files changed, 111 insertions(+) create mode 100644 mission/controller/acs/control/Detumble.cpp create mode 100644 mission/controller/acs/control/Detumble.h diff --git a/mission/controller/acs/control/Detumble.cpp b/mission/controller/acs/control/Detumble.cpp new file mode 100644 index 00000000..283d6dc1 --- /dev/null +++ b/mission/controller/acs/control/Detumble.cpp @@ -0,0 +1,65 @@ + +/* + * Detumble.cpp + * + * Created on: 17 Aug 2022 + * Author: Robin Marquardt + */ + + +#include "Detumble.h" +#include +#include +#include +#include +#include +#include +#include + + +Detumble::Detumble(AcsParameters *acsParameters_){ + loadAcsParameters(acsParameters_); +} + +Detumble::~Detumble(){ + +} + +void Detumble::loadAcsParameters(AcsParameters *acsParameters_){ + + detumbleCtrlParameters = &(acsParameters_->detumbleCtrlParameters); + magnetorquesParameter = &(acsParameters_->magnetorquesParameter); + +} + + +ReturnValue_t Detumble::bDotLaw(const double *magRate, const bool *magRateValid, + const double *magField, const bool *magFieldValid, + double *magMom) { + + if (!magRateValid || !magFieldValid) { + return DETUMBLE_NO_SENSORDATA; + } + double gain = detumbleCtrlParameters->gainD; + double factor = -gain / pow(VectorOperations::norm(magField,3),2); + VectorOperations::mulScalar(magRate, factor, magMom, 3); + return RETURN_OK; + +} + +ReturnValue_t Detumble::bangbangLaw(const double *magRate, const bool *magRateValid, double *magMom) { + + if (!magRateValid) { + return DETUMBLE_NO_SENSORDATA; + } + + double dipolMax = magnetorquesParameter->DipolMax; + for (int i = 0; i<3; i++) { + + magMom[i] = - dipolMax * sign(magRate[i]); + + } + + return RETURN_OK; + +} diff --git a/mission/controller/acs/control/Detumble.h b/mission/controller/acs/control/Detumble.h new file mode 100644 index 00000000..54d62179 --- /dev/null +++ b/mission/controller/acs/control/Detumble.h @@ -0,0 +1,46 @@ +/* + * Detumble.h + * + * Created on: 17 Aug 2022 + * Author: Robin Marquardt + */ + +#ifndef ACS_CONTROL_DETUMBLE_H_ +#define ACS_CONTROL_DETUMBLE_H_ + +#include +#include +#include +#include +#include +#include "acs/config/classIds.h" +#include +#include + +class Detumble : public HasReturnvaluesIF { + +public: + Detumble(AcsParameters *acsParameters_); + virtual ~Detumble(); + + static const uint8_t INTERFACE_ID = CLASS_ID::DETUMBLE; + static const ReturnValue_t DETUMBLE_NO_SENSORDATA = MAKE_RETURN_CODE(0x01); + + /* @brief: Load AcsParameters für 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); + + ReturnValue_t bangbangLaw(const double *magRate, const bool *magRateValid, double *magMom); + +private: + AcsParameters::DetumbleCtrlParameters* detumbleCtrlParameters; + AcsParameters::MagnetorquesParameter* magnetorquesParameter; +}; + +#endif /* ACS_CONTROL_DETUMBLE_H_ */ + -- 2.34.1 From 497149a628a72ac848c5a33e3a2db79465699ffb Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 20 Sep 2022 13:43:26 +0200 Subject: [PATCH 015/101] added PtgCtrl --- mission/controller/acs/control/PtgCtrl.cpp | 165 +++++++++++++++++++++ mission/controller/acs/control/PtgCtrl.h | 60 ++++++++ 2 files changed, 225 insertions(+) create mode 100644 mission/controller/acs/control/PtgCtrl.cpp create mode 100644 mission/controller/acs/control/PtgCtrl.h diff --git a/mission/controller/acs/control/PtgCtrl.cpp b/mission/controller/acs/control/PtgCtrl.cpp new file mode 100644 index 00000000..eaffd909 --- /dev/null +++ b/mission/controller/acs/control/PtgCtrl.cpp @@ -0,0 +1,165 @@ +/* + * PtgCtrl.cpp + * + * Created on: 17 Jul 2022 + * Author: Robin Marquardt + */ + + + +#include "PtgCtrl.h" +#include +#include +#include +#include +#include +#include +#include + +PtgCtrl::PtgCtrl(AcsParameters *acsParameters_){ + loadAcsParameters(acsParameters_); +} + +PtgCtrl::~PtgCtrl(){ + +} + +void PtgCtrl::loadAcsParameters(AcsParameters *acsParameters_){ + pointingModeControllerParameters = &(acsParameters_->targetModeControllerParameters); + inertiaEIVE = &(acsParameters_->inertiaEIVE); + rwHandlingParameters = &(acsParameters_->rwHandlingParameters); + rwMatrices =&(acsParameters_->rwMatrices); +} + +void PtgCtrl::ptgGroundstation(const double mode, const double *qError, const double *deltaRate,const double *rwPseudoInv, double *torqueRws){ + + //------------------------------------------------------------------------------------------------ + // Compute gain matrix K and P matrix + //------------------------------------------------------------------------------------------------ + double om = pointingModeControllerParameters->om; + double zeta = pointingModeControllerParameters->zeta; + double qErrorMin = pointingModeControllerParameters->qiMin; + double omMax = pointingModeControllerParameters->omMax; + + double cInt = 2 * om * zeta; + double kInt = 2 * pow(om,2); + + double qErrorLaw[3] = {0, 0, 0}; + + for (int i = 0; i < 3; i++) { + if (abs(qError[i]) < qErrorMin) { + qErrorLaw[i] = qErrorMin; + } + else { + qErrorLaw[i] = abs(qError[i]); + } + } + double qErrorLawNorm = VectorOperations::norm(qErrorLaw, 3); + + double gain1 = cInt * omMax / qErrorLawNorm; + double gainVector[3] = {0, 0, 0}; + VectorOperations::mulScalar(qErrorLaw, gain1, gainVector, 3); + + double gainMatrixDiagonal[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double gainMatrix[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + gainMatrixDiagonal[0][0] = gainVector[0]; + gainMatrixDiagonal[1][1] = gainVector[1]; + gainMatrixDiagonal[2][2] = gainVector[2]; + MatrixOperations::multiply( *gainMatrixDiagonal, *(inertiaEIVE->inertiaMatrix), *gainMatrix, 3, 3, 3); + + // Inverse of gainMatrix + double gainMatrixInverse[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + gainMatrixInverse[0][0] = 1 / gainMatrix[0][0]; + gainMatrixInverse[1][1] = 1 / gainMatrix[1][1]; + 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::multiplyScalar(*pMatrix, kInt, *pMatrix, 3, 3); + + //------------------------------------------------------------------------------------------------ + // Torque Calculations for the reaction wheels + //------------------------------------------------------------------------------------------------ + + double pError[3] = {0, 0, 0}; + MatrixOperations::multiply(*pMatrix, qError, pError, 3, 3, 1); + double pErrorSign[3] = {0, 0, 0}; + + for (int i = 0; i < 3; i++) { + + if (abs(pError[i]) > 1) { + pErrorSign[i] = sign(pError[i]); + } + else { + pErrorSign[i] = pError[i]; + } + } +// 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 + double torqueRate[3] = {0, 0, 0}; + MatrixOperations::multiply(*(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 + double torque[3] = {0, 0, 0}; + VectorOperations::add(torqueRate, torqueQuat, torque, 3); + MatrixOperations::multiply(rwPseudoInv, torque, torqueRws, 4, 3, 1); + +} + +void PtgCtrl::ptgDesaturation(double *magFieldEst, bool *magFieldEstValid, double *satRate, double *speedRw0, + double *speedRw1, double *speedRw2, double *speedRw3, double *mgtDpDes) { + if ( !(magFieldEstValid) || !(pointingModeControllerParameters->desatOn)) { + + mgtDpDes[0] = 0; + mgtDpDes[1] = 0; + mgtDpDes[2] = 0; + return; + + } + +// calculating momentum of satellite and momentum of reaction wheels + double speedRws[4] = {*speedRw0, *speedRw1, *speedRw2, *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); + double momentumSat[3] = {0, 0, 0}, momentumTotal[3] = {0, 0, 0}; + MatrixOperations::multiply(*(inertiaEIVE->inertiaMatrix), satRate, momentumSat, 3, 3, 1); + VectorOperations::add(momentumSat, momentumRw, momentumTotal, 3); +// calculating momentum error + double deltaMomentum[3] = {0, 0, 0}; + VectorOperations::subtract(momentumTotal, pointingModeControllerParameters->desatMomentumRef, deltaMomentum, 3); +// resulting magnetic dipole command + double crossMomentumMagField[3] = {0, 0, 0}; + VectorOperations::cross(deltaMomentum, magFieldEst, crossMomentumMagField); + double normMag = VectorOperations::norm(magFieldEst, 3), factor = 0; + factor = (pointingModeControllerParameters->deSatGainFactor) / normMag; + VectorOperations::mulScalar(crossMomentumMagField, factor, mgtDpDes, 3); + +} + +void PtgCtrl::ptgNullspace(const double *speedRw0, const double *speedRw1, const double *speedRw2, const double *speedRw3, double *rwTrqNs) { + + double speedRws[4] = {*speedRw0, *speedRw1, *speedRw2, *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 + VectorOperations::mulScalar(rpmOffset, factor, rpmOffset, 4); + 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, wheelMomentum, 4); + double gainNs = pointingModeControllerParameters->gainNullspace; + double nullSpaceMatrix[4][4] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MathOperations::vecTransposeVecMatrix(rwMatrices->nullspace, rwMatrices->nullspace, *nullSpaceMatrix, 4); + MatrixOperations::multiply(*nullSpaceMatrix, wheelMomentum, rwTrqNs, 4, 4, 1); + VectorOperations::mulScalar(rwTrqNs, gainNs, rwTrqNs, 4); + VectorOperations::mulScalar(rwTrqNs, -1, rwTrqNs, 4); + + +} diff --git a/mission/controller/acs/control/PtgCtrl.h b/mission/controller/acs/control/PtgCtrl.h new file mode 100644 index 00000000..5bd7f0da --- /dev/null +++ b/mission/controller/acs/control/PtgCtrl.h @@ -0,0 +1,60 @@ +/* + * 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_ + +#include +#include +#include +#include +#include +#include "acs/config/classIds.h" +#include +#include + +class PtgCtrl : public HasReturnvaluesIF { + +public: + /* @brief: Constructor + * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters + */ + PtgCtrl(AcsParameters *acsParameters_); + virtual ~PtgCtrl(); + + static const uint8_t INTERFACE_ID = CLASS_ID::PTG; + static const ReturnValue_t PTGCTRL_MEKF_INPUT_INVALID = MAKE_RETURN_CODE(0x01); + + /* @brief: Load AcsParameters für 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 ptgGroundstation(const double mode,const double *qError,const double *deltaRate,const double *rwPseudoInv, double *torqueRws); + + void ptgDesaturation(double *magFieldEst, bool *magFieldEstValid, double *satRate, double *speedRw0, + double *speedRw1, double *speedRw2, double *speedRw3, double *mgtDpDes); + + void ptgNullspace(const double *speedRw0, const double *speedRw1, const double *speedRw2, const double *speedRw3, double *rwTrqNs); + +private: + AcsParameters::PointingModeControllerParameters* pointingModeControllerParameters; + AcsParameters::RwHandlingParameters* rwHandlingParameters; + AcsParameters::InertiaEIVE* inertiaEIVE; + AcsParameters::RWMatrices* rwMatrices; +}; + +#endif /* ACS_CONTROL_PTGCTRL_H_ */ -- 2.34.1 From 40917ab988cb074e60aafc1ad9cc9e21fe88bed7 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 20 Sep 2022 13:46:42 +0200 Subject: [PATCH 016/101] added SafeCtrl --- mission/controller/acs/control/SafeCtrl.cpp | 186 ++++++++++++++++++++ mission/controller/acs/control/SafeCtrl.h | 63 +++++++ 2 files changed, 249 insertions(+) create mode 100644 mission/controller/acs/control/SafeCtrl.cpp create mode 100644 mission/controller/acs/control/SafeCtrl.h diff --git a/mission/controller/acs/control/SafeCtrl.cpp b/mission/controller/acs/control/SafeCtrl.cpp new file mode 100644 index 00000000..55772ae4 --- /dev/null +++ b/mission/controller/acs/control/SafeCtrl.cpp @@ -0,0 +1,186 @@ +/* + * SafeCtrl.cpp + * + * Created on: 19 Apr 2022 + * Author: Robin Marquardt + */ + +#include "SafeCtrl.h" +#include +#include +#include +#include +#include +#include + +SafeCtrl::SafeCtrl(AcsParameters *acsParameters_){ + loadAcsParameters(acsParameters_); + MatrixOperations::multiplyScalar(*(inertiaEIVE->inertiaMatrix), 10, *gainMatrixInertia, 3, 3); +} + +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, bool *rateMekfValid, + double *sunDirRef, double *satRatRef, + double *outputMagMomB, bool *outputValid){ + + if ( !(*quatBJValid) || !(*magFieldModelValid) || !(*sunDirModelValid) || + !(*rateMekfValid)) { + *outputValid = false; + return SAFECTRL_MEKF_INPUT_INVALID; + } + + double kRate = 0, kAlign = 0; + kRate = safeModeControllerParameters->k_rate_mekf; + kAlign = 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}}; + MathOperations::dcmFromQuat(quatBJ, *dcmBJ); + double sunDirB[3] = {0,0,0}, magFieldB[3] = {0,0,0}; + MatrixOperations::multiply(*dcmBJ, sunDirModel, sunDirB, 3, 3, 1); + MatrixOperations::multiply(*dcmBJ, magFieldModel, magFieldB, 3, 3, 1); + + double crossSun[3] = {0, 0, 0}; + + VectorOperations::cross(sunDirRef, sunDirB, crossSun); + double normCrossSun = VectorOperations::norm(crossSun, 3); + +// calc angle alpha between sunDirRef and sunDIr + double alpha = 0, dotSun = 0; + dotSun = VectorOperations::dot(sunDirRef, sunDirB); + alpha = acos(dotSun); + +// Law Torque calculations + double torqueCmd[3] = {0, 0, 0}, torqueAlign[3] = {0, 0, 0}, + torqueRate[3] = {0, 0, 0}, torqueAll[3] = {0, 0, 0}; + + double scalarFac = 0; + scalarFac = kAlign * alpha / normCrossSun; + VectorOperations::mulScalar(crossSun, scalarFac, torqueAlign, 3); + + double rateSafeMode[3] = {0,0,0}; + VectorOperations::subtract(satRateMekf, satRatRef, rateSafeMode, 3); + VectorOperations::mulScalar(rateSafeMode, -kRate, torqueRate, 3); + + VectorOperations::add(torqueRate, torqueAlign, torqueAll, 3); +// Adding factor of inertia for axes + MatrixOperations::multiply(*gainMatrixInertia, torqueAll, torqueCmd, 3, 3, 1); + +// MagMom B (orthogonal torque) + double torqueMgt[3] = {0,0,0}; + VectorOperations::cross(magFieldB, torqueCmd, torqueMgt); + double normMag = VectorOperations::norm(magFieldB, 3); + VectorOperations::mulScalar(torqueMgt, 1/pow(normMag,2), outputMagMomB, 3); + *outputValid = true; + + return RETURN_OK; + +} + +// Will be the version in worst case scenario in event of no working MEKF (nor RMUs) +void SafeCtrl::safeNoMekf(timeval now, double *susDirB, bool *susDirBValid, + double *sunRateB, bool *sunRateBValid, + double *magFieldB, bool *magFieldBValid, + double *magRateB, bool *magRateBValid, + double *sunDirRef, double *satRateRef, + double *outputMagMomB, bool *outputValid){ + +// Check for invalid Inputs + if ( !susDirBValid || !magFieldBValid || !magRateBValid) { + *outputValid = false; + return; + } + +// normalize sunDir and magDir + double magDirB[3] = {0, 0, 0}; + VectorOperations::normalize(magFieldB, magDirB, 3); + VectorOperations::normalize(susDirB, susDirB, 3); + +// Cosinus angle between sunDir and magDir + double cosAngleSunMag = VectorOperations::dot(magDirB, susDirB); + +// Rate parallel to sun direction and magnetic field direction + double rateParaSun = 0, rateParaMag = 0; + double dotSunRateMag = 0, dotmagRateSun = 0, + rateFactor = 0; + dotSunRateMag = VectorOperations::dot(sunRateB, magDirB); + dotmagRateSun = VectorOperations::dot(magRateB, susDirB); + rateFactor = 1 - pow(cosAngleSunMag,2); + rateParaSun = ( dotmagRateSun + cosAngleSunMag * dotSunRateMag ) / rateFactor; + rateParaMag = ( dotSunRateMag + cosAngleSunMag * dotmagRateSun ) / rateFactor; + +// Full rate or estimate + double estSatRate[3] = {0, 0, 0}; + double estSatRateMag[3] = {0, 0, 0}, estSatRateSun[3] = {0, 0, 0}; + VectorOperations::mulScalar(susDirB, rateParaSun, estSatRateSun, 3); + VectorOperations::add(sunRateB, estSatRateSun, estSatRateSun, 3); + VectorOperations::mulScalar(magDirB, rateParaMag, estSatRateMag, 3); + VectorOperations::add(magRateB, estSatRateMag, estSatRateMag, 3); + VectorOperations::add(estSatRateSun, estSatRateMag, estSatRate, 3); + VectorOperations::mulScalar(estSatRate, 0.5, estSatRate, 3); + +/* Only valid if angle between sun direction and magnetic field direction + is sufficiently large */ + + double sinAngle = 0; + sinAngle = sin(acos(cos(cosAngleSunMag))); + + if ( !(sinAngle > sin( safeModeControllerParameters->sunMagAngleMin * M_PI / 180))) { + return; + } + +// Rate for Torque Calculation + double diffRate[3] = {0, 0, 0}; /* ADD TO MONITORING */ + VectorOperations::subtract(estSatRate, satRateRef, diffRate, 3); + +// Torque Align calculation + double kRateNoMekf = 0, kAlignNoMekf = 0; + kRateNoMekf = safeModeControllerParameters->k_rate_no_mekf; + kAlignNoMekf = safeModeControllerParameters->k_align_no_mekf; + + double cosAngleAlignErr = VectorOperations::dot(sunDirRef, susDirB); + double crossSusSunRef[3] = {0, 0, 0}; + VectorOperations::cross(sunDirRef, susDirB, crossSusSunRef); + double sinAngleAlignErr = VectorOperations::norm(crossSusSunRef, 3); + + double torqueAlign[3] = {0, 0, 0}; + double angleAlignErr = acos(cosAngleAlignErr); + double torqueAlignFactor = kAlignNoMekf * angleAlignErr / sinAngleAlignErr; + VectorOperations::mulScalar(crossSusSunRef, torqueAlignFactor, torqueAlign, 3); + +//Torque Rate Calculations + double torqueRate[3] = {0, 0, 0}; + VectorOperations::mulScalar(diffRate, -kRateNoMekf, torqueRate, 3); + +//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); + +//Magnetic moment + double magMomB[3] = {0, 0, 0}; + double crossMagFieldTorque[3] = {0, 0, 0}; + VectorOperations::cross(magFieldB, torqueB, crossMagFieldTorque); + double magMomFactor = pow( VectorOperations::norm(magFieldB, 3), 2 ); + VectorOperations::mulScalar(crossMagFieldTorque, 1/magMomFactor, magMomB, 3); + + outputMagMomB[0] = magMomB[0]; + outputMagMomB[1] = magMomB[1]; + outputMagMomB[2] = magMomB[2]; + + *outputValid = true; + +} + + diff --git a/mission/controller/acs/control/SafeCtrl.h b/mission/controller/acs/control/SafeCtrl.h new file mode 100644 index 00000000..b0ce6a90 --- /dev/null +++ b/mission/controller/acs/control/SafeCtrl.h @@ -0,0 +1,63 @@ +/* + * safeCtrl.h + * + * Created on: 19 Apr 2022 + * Author: rooob + */ + +#ifndef SAFECTRL_H_ +#define SAFECTRL_H_ + +#include +#include +#include +#include +#include +#include "acs/config/classIds.h" +#include +#include + +class SafeCtrl : public HasReturnvaluesIF { + +public: + + SafeCtrl(AcsParameters *acsParameters_); + virtual ~SafeCtrl(); + + static const uint8_t INTERFACE_ID = CLASS_ID::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, double *satRatRef, // From Guidance (!) + double *outputMagMomB, bool *outputValid); + + void safeNoMekf(timeval now, double *susDirB, bool *susDirBValid, + double *sunRateB, bool *sunRateBValid, + double *magFieldB, bool *magFieldBValid, + double *magRateB, bool *magRateBValid, + double *sunDirRef, double *satRateRef, + double *outputMagMomB, bool *outputValid); + + void idleSunPointing(); // with reaction wheels + +protected: + +private: + AcsParameters::SafeModeControllerParameters* safeModeControllerParameters; + AcsParameters::InertiaEIVE* inertiaEIVE; + double gainMatrixInertia[3][3]; + + double magFieldBState[3]; + timeval magFieldBStateTime; + +}; + + + +#endif /* ACS_CONTROL_SAFECTRL_H_ */ + -- 2.34.1 From 858b291f6105aef27dde6d8daa22a14d84d482a5 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 20 Sep 2022 13:52:17 +0200 Subject: [PATCH 017/101] added config. added classIds --- mission/controller/acs/config/classIds.h | 24 ++++++++++++++++++++++++ 1 file changed, 24 insertions(+) create mode 100644 mission/controller/acs/config/classIds.h diff --git a/mission/controller/acs/config/classIds.h b/mission/controller/acs/config/classIds.h new file mode 100644 index 00000000..0c03b408 --- /dev/null +++ b/mission/controller/acs/config/classIds.h @@ -0,0 +1,24 @@ +/* + * classIds.h + * + * Created on: 1 Mar 2022 + * Author: rooob + */ + +#ifndef ACS_CONFIG_CLASSIDS_H_ +#define ACS_CONFIG_CLASSIDS_H_ +#include "bsp_hosted/fsfwconfig/returnvalues/classIds.h" + +namespace CLASS_ID { +enum eiveclassIds: uint8_t { + EIVE_CLASS_ID_START = CLASS_ID_END, + KALMAN, + SAFE, + PTG, + DETUMBLE, + EIVE_CLASS_ID_END // [EXPORT] : [END] +}; +} + + +#endif /* ACS_CONFIG_CLASSIDS_H_ */ -- 2.34.1 From 7885205a0740d4866ee9a48b0a48d5a2d9fcb882 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 20 Sep 2022 14:15:55 +0200 Subject: [PATCH 018/101] added Navitation --- mission/controller/acs/Navigation.h | 35 +++++++++++++++++++ mission/controller/acs/Navitation.cpp | 49 +++++++++++++++++++++++++++ 2 files changed, 84 insertions(+) create mode 100644 mission/controller/acs/Navigation.h create mode 100644 mission/controller/acs/Navitation.cpp diff --git a/mission/controller/acs/Navigation.h b/mission/controller/acs/Navigation.h new file mode 100644 index 00000000..7d71df99 --- /dev/null +++ b/mission/controller/acs/Navigation.h @@ -0,0 +1,35 @@ +/* + * Navigation.h + * + * Created on: 19 Apr 2022 + * Author: Robin Marquardt + */ + +#ifndef NAVIGATION_H_ +#define NAVIGATION_H_ + + +#include "AcsParameters.h" +#include "SensorProcessing.h" +#include +#include +#include + +class Navigation{ +public: + Navigation(AcsParameters *acsParameters_); //Input mode ? + virtual ~Navigation(); + + void useMekf(ACS::SensorValues* sensorValues, ACS::OutputValues *outputValues, ReturnValue_t *mekfValid); + void processSensorData(); + +protected: + +private: + MultiplicativeKalmanFilter multiplicativeKalmanFilter; + AcsParameters acsParameters; + bool kalmanInit = false; +}; + +#endif /* ACS_NAVIGATION_H_ */ + diff --git a/mission/controller/acs/Navitation.cpp b/mission/controller/acs/Navitation.cpp new file mode 100644 index 00000000..50dbb049 --- /dev/null +++ b/mission/controller/acs/Navitation.cpp @@ -0,0 +1,49 @@ +/* + * Navigation.cpp + * + * Created on: 23 May 2022 + * Author: Robin Marquardt + */ + +#include "Navigation.h" +#include +#include +#include +#include +#include +#include + +Navigation::Navigation(AcsParameters *acsParameters_): multiplicativeKalmanFilter(acsParameters_){ + acsParameters = *acsParameters_; +} + +Navigation::~Navigation(){ + +} + +void Navigation::useMekf(ACS::SensorValues* sensorValues, ACS::OutputValues *outputValues, ReturnValue_t *mekfValid){ + + if (kalmanInit) { + *mekfValid = multiplicativeKalmanFilter.mekfEst(sensorValues->quatJB, &sensorValues->quatJBValid, + outputValues->satRateEst, &outputValues->satRateEstValid, + outputValues->magFieldEst, &outputValues->magFieldEstValid, + outputValues->sunDirEst, &outputValues->sunDirEstValid, + outputValues->sunDirModel, &outputValues->sunDirModelValid, + outputValues->magFieldModel, &outputValues->magFieldModelValid, + outputValues->quatMekfBJ, outputValues->satRateMekf); // VALIDS FOR QUAT AND RATE ?? + + } + else { + multiplicativeKalmanFilter.init(outputValues->magFieldEst, &outputValues->magFieldEstValid, + outputValues->sunDirEst, &outputValues->sunDirEstValid, + outputValues->sunDirModel, &outputValues->sunDirModelValid, + outputValues->magFieldModel, &outputValues->magFieldModelValid); + kalmanInit = true; + *mekfValid = 0; + +// Maybe we need feedback from kalmanfilter to identify if there was a problem with the init of kalman filter +// where does this class know from that kalman filter was not initialized ? + } +} + + -- 2.34.1 From 5ebdc9e7676aea838b2dce730c148d1cce3b2cb5 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 20 Sep 2022 15:06:05 +0200 Subject: [PATCH 019/101] amended includes. removed links to HasParametersIF --- mission/controller/acs/AcsParameters.h | 2 +- mission/controller/acs/ActuatorCmd.cpp | 14 +++++++------- mission/controller/acs/ActuatorCmd.h | 10 +++++----- mission/controller/acs/Guidance.h | 2 +- mission/controller/acs/Igrf13Model.h | 2 +- mission/controller/acs/Navigation.h | 10 +++++----- mission/controller/acs/Navitation.cpp | 4 ++-- mission/controller/acs/SensorProcessing.cpp | 10 +++++----- mission/controller/acs/SensorProcessing.h | 14 +++++++------- mission/controller/acs/control/Detumble.cpp | 12 ++++++------ mission/controller/acs/control/Detumble.h | 10 +++++----- mission/controller/acs/util/MathOperations.h | 1 + 12 files changed, 46 insertions(+), 45 deletions(-) diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index b4e32d65..6e8fd1a2 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -10,7 +10,7 @@ typedef unsigned char uint8_t; -class AcsParameters:public HasParametersIF{ +class AcsParameters/*:public HasParametersIF*/{ public: AcsParameters(); diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index 25eeca9c..3b4ed71e 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -6,14 +6,14 @@ */ -#include "ActuatorCmd.h" -#include +#include +#include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include ActuatorCmd::ActuatorCmd(AcsParameters *acsParameters_) { acsParameters = *acsParameters_; diff --git a/mission/controller/acs/ActuatorCmd.h b/mission/controller/acs/ActuatorCmd.h index 9b721505..85ef1532 100644 --- a/mission/controller/acs/ActuatorCmd.h +++ b/mission/controller/acs/ActuatorCmd.h @@ -9,11 +9,11 @@ #define ACTUATORCMD_H_ -#include "AcsParameters.h" -#include "SensorProcessing.h" -#include -#include -#include +#include +#include +#include +#include +#include class ActuatorCmd{ public: diff --git a/mission/controller/acs/Guidance.h b/mission/controller/acs/Guidance.h index 736d8b9b..76cfce77 100644 --- a/mission/controller/acs/Guidance.h +++ b/mission/controller/acs/Guidance.h @@ -12,7 +12,7 @@ #include #include #include -#include +#include class Guidance { diff --git a/mission/controller/acs/Igrf13Model.h b/mission/controller/acs/Igrf13Model.h index 6e46a90e..b6f14e0f 100644 --- a/mission/controller/acs/Igrf13Model.h +++ b/mission/controller/acs/Igrf13Model.h @@ -25,7 +25,7 @@ // Output should be transformed to [T] instead of [nT] // Updating Coefficients has to be implemented yet. Question, updating everyday ? -class Igrf13Model:public HasParametersIF{ +class Igrf13Model/*:public HasParametersIF*/{ public: Igrf13Model(); diff --git a/mission/controller/acs/Navigation.h b/mission/controller/acs/Navigation.h index 7d71df99..75bbade5 100644 --- a/mission/controller/acs/Navigation.h +++ b/mission/controller/acs/Navigation.h @@ -9,11 +9,11 @@ #define NAVIGATION_H_ -#include "AcsParameters.h" -#include "SensorProcessing.h" -#include -#include -#include +#include +#include +#include +#include +#include class Navigation{ public: diff --git a/mission/controller/acs/Navitation.cpp b/mission/controller/acs/Navitation.cpp index 50dbb049..2cb70389 100644 --- a/mission/controller/acs/Navitation.cpp +++ b/mission/controller/acs/Navitation.cpp @@ -7,11 +7,11 @@ #include "Navigation.h" #include -#include +#include #include #include #include -#include +#include Navigation::Navigation(AcsParameters *acsParameters_): multiplicativeKalmanFilter(acsParameters_){ acsParameters = *acsParameters_; diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index eeb7f457..7b89daf1 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -6,11 +6,11 @@ */ #include "SensorProcessing.h" -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include #include diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h index 9db8e25b..43c93722 100644 --- a/mission/controller/acs/SensorProcessing.h +++ b/mission/controller/acs/SensorProcessing.h @@ -6,12 +6,12 @@ #define SENSORPROCESSING_H_ #include //uint8_t -#include /*purpose, timeval ?*/ -#include "acs/config/classIds.h" -#include -#include "AcsParameters.h" -#include -#include +#include /*purpose, timeval ?*/ +#include +#include +#include +#include +#include /*Planned: * - Fusion of Sensor Measurements - @@ -25,7 +25,7 @@ * magField * SunDirEst*/ -class SensorProcessing: public HasReturnvaluesIF{ +class SensorProcessing{ public: void reset(); diff --git a/mission/controller/acs/control/Detumble.cpp b/mission/controller/acs/control/Detumble.cpp index 283d6dc1..8c3bdf86 100644 --- a/mission/controller/acs/control/Detumble.cpp +++ b/mission/controller/acs/control/Detumble.cpp @@ -7,14 +7,14 @@ */ -#include "Detumble.h" -#include -#include +#include +#include +#include #include -#include -#include +#include +#include #include -#include +#include Detumble::Detumble(AcsParameters *acsParameters_){ diff --git a/mission/controller/acs/control/Detumble.h b/mission/controller/acs/control/Detumble.h index 54d62179..47efd49d 100644 --- a/mission/controller/acs/control/Detumble.h +++ b/mission/controller/acs/control/Detumble.h @@ -13,11 +13,11 @@ #include #include #include -#include "acs/config/classIds.h" -#include -#include +#include +#include +#include -class Detumble : public HasReturnvaluesIF { +class Detumble{ public: Detumble(AcsParameters *acsParameters_); @@ -42,5 +42,5 @@ private: AcsParameters::MagnetorquesParameter* magnetorquesParameter; }; -#endif /* ACS_CONTROL_DETUMBLE_H_ */ +#endif ACS_CONTROL_DETUMBLE_H_ diff --git a/mission/controller/acs/util/MathOperations.h b/mission/controller/acs/util/MathOperations.h index 82d19b19..6a534880 100644 --- a/mission/controller/acs/util/MathOperations.h +++ b/mission/controller/acs/util/MathOperations.h @@ -9,6 +9,7 @@ #define MATH_MATHOPERATIONS_H_ #include +#include #include #include #include -- 2.34.1 From b2484136b10826af2a72ddfbea623853b50cfd7c Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 20 Sep 2022 15:45:49 +0200 Subject: [PATCH 020/101] further fixes for HasReturnValuesIF --- mission/controller/acs/Guidance.cpp | 2 +- mission/controller/acs/SensorValues.cpp | 2 +- mission/controller/acs/SensorValues.h | 4 ++-- mission/controller/acs/control/Detumble.cpp | 4 ++-- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/mission/controller/acs/Guidance.cpp b/mission/controller/acs/Guidance.cpp index d861769d..158ee9f0 100644 --- a/mission/controller/acs/Guidance.cpp +++ b/mission/controller/acs/Guidance.cpp @@ -74,7 +74,7 @@ void Guidance::targetQuatPtg(ACS::SensorValues* sensorValues, ACS::OutputValues // TEST SECTION ! double dcmTEST[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - MatrixOperations::multiply(&acsParameters.magnetorquesParameter.mtq0orientationMatrix, dcmTEST, dcmTEST, 3, 3, 3); + //MatrixOperations::multiply(&acsParameters.magnetorquesParameter.mtq0orientationMatrix, dcmTEST, dcmTEST, 3, 3, 3); MatrixOperations::multiply(*dcmDot, *dcmEJ, *dcmEJDot, 3, 3, 3); MatrixOperations::multiplyScalar(*dcmEJDot, omegaEarth, *dcmEJDot, 3, 3); diff --git a/mission/controller/acs/SensorValues.cpp b/mission/controller/acs/SensorValues.cpp index f3a52dea..25f2d61f 100644 --- a/mission/controller/acs/SensorValues.cpp +++ b/mission/controller/acs/SensorValues.cpp @@ -28,7 +28,7 @@ ReturnValue_t SensorValues::update() { // quatJB[3] = static_cast(quaternion.value); // quatJBValid = quaternion.isValid(); - return RETURN_OK; + return returnvalue::OK; } } diff --git a/mission/controller/acs/SensorValues.h b/mission/controller/acs/SensorValues.h index 1a328e16..566eec81 100644 --- a/mission/controller/acs/SensorValues.h +++ b/mission/controller/acs/SensorValues.h @@ -5,11 +5,11 @@ #ifndef SENSORVALUES_H_ #define SENSORVALUES_H_ -#include +#include namespace ACS { -class SensorValues: public HasReturnvaluesIF { +class SensorValues{ public: SensorValues(); virtual ~SensorValues(); diff --git a/mission/controller/acs/control/Detumble.cpp b/mission/controller/acs/control/Detumble.cpp index 8c3bdf86..8a15aa8a 100644 --- a/mission/controller/acs/control/Detumble.cpp +++ b/mission/controller/acs/control/Detumble.cpp @@ -43,7 +43,7 @@ ReturnValue_t Detumble::bDotLaw(const double *magRate, const bool *magRateValid, double gain = detumbleCtrlParameters->gainD; double factor = -gain / pow(VectorOperations::norm(magField,3),2); VectorOperations::mulScalar(magRate, factor, magMom, 3); - return RETURN_OK; + return returnvalue::OK; } @@ -60,6 +60,6 @@ ReturnValue_t Detumble::bangbangLaw(const double *magRate, const bool *magRateVa } - return RETURN_OK; + return returnvalue::OK; } -- 2.34.1 From 798668673941daaaa1a484c6d530c7d1ebe9934a Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 22 Sep 2022 13:39:42 +0200 Subject: [PATCH 021/101] added SUS calibration coefficients to AcsParameters --- mission/controller/acs/AcsParameters.cpp | 677 ++++++++++++++++++++++- mission/controller/acs/AcsParameters.h | 25 + 2 files changed, 701 insertions(+), 1 deletion(-) diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index 7f5b26c1..92273e04 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -1,7 +1,7 @@ #include #include "AcsParameters.h" -//#include +#include #include AcsParameters::AcsParameters() { @@ -34,6 +34,681 @@ AcsParameters::AcsParameters() { {-1, 0, 0}, { 0, 1, 0}}; + + susHandlingParameters.sus0coeffAlpha = { + {10.4400948050067, 1.38202655603079, 0.975299591736672, 0.0172133914423707, -0.0163482459492803, + 0.035730152619911, 0.00021725657060767, -0.000181685375645396, -0.000124096561459262, + 0.00040790566176981}, + {6.38281281805793, 1.81388255990089, 0.28679524291736, 0.0218036823758417, 0.010516766426651, + 0.000446101708841615, 0.00020187044149361, 0.000114957457831415, 1.63114413539632e-05, + -2.0187452317724e-05}, + {-29.3049094555, -0.506844002611835, 1.64911970541112, -0.0336282997119334, 0.053185806861685, + -0.028164943139695, -0.00021098074590512, 0.000643681643489995, -0.000249094601806692, + 0.000231466668650876}, + {-4.76233790255328, 1.1780710601961, -0.194257188545164, 0.00471817228628384, + -0.00183773644319332, -0.00570261621182479, -7.99203367291902e-05, 7.75752247926601e-05, + -9.78534772816957e-06, -4.72083745991256e-05}, + {0.692159025649028, 1.11895461388667, 0.341706834956496, 0.000237989648019541, + -0.000188322779563912, 0.000227310789253953, 0.000133001646828401, -0.000305810826248463, + 0.00010150571088124, -0.000367705461590854}, + {3.38094203317731, 1.24778838596815, 0.067807236112956, -0.00379395536123526, + -0.00339180589343601, -0.00188754615986649, -7.52406312245606e-05, 4.58398750278147e-05, + 6.97244631313601e-05, 2.50519145070895e-05}, + {-7.10546287716029, 0.459472977452686, -1.12251049944014, 0.0175406972371191, + -0.0310525406867782, -0.0531315970690727, -0.000121107664597462, 0.000544665437051928, + -1.78466217018177e-05, -0.00058976234038192}, + {1.60633684055984, 1.1975095485662, 0.180159204664965, -0.00259157601062089, + -0.0038106317634397, 0.000956686555225968, 4.28416721502134e-06, 5.84532336259517e-06, + -2.73407888222758e-05, 5.45131881032866e-06}, + {43.3732235586222, 0.528096786861784, -3.41255850703983, -0.0161629934278675, + 0.0790998053536612, 0.0743822668655928, 0.000237176965460634, -0.000426691336904078, + -0.000889196131314391, -0.000509766491897672}}; + susHandlingParameters.sus0coeffBeta = { + {1.03872648284911, -0.213507239271552, 1.43193059498181, -0.000972717820830235, + -0.00661046096415371, 0.00974284211491888, 2.96098456891215e-05, -8.2933115634257e-05, + -5.52178824394723e-06, 5.73935295303589e-05}, + {3.42242235823356, 0.0848392511283237, 1.24574390342586, 0.00356248195980133, + 0.00100415659893053, -0.00460120247716139, 3.84891005422427e-05, 2.70236417852327e-05, + -7.58501977656551e-05, -8.79809730730992e-05}, + {14.0092526123741, 1.03126714946215, 1.0611008563785, 0.04076462444523, 0.0114106419194518, + 0.00746959159048058, 0.000388033225774727, -0.000124645014888926, -0.000296639947532341, + -0.00020861690864945}, + {1.3562422681189, -0.241585615891602, 1.49170424068611, 0.000179184170448335, + -0.00712399257616284, 0.0121433526723498, 3.29770580642447e-05, 8.78960210966787e-06, + -6.00508568552101e-05, 0.000101583822589461}, + {-0.718855428908583, -0.344067476078684, 1.12397093701762, 0.000236505431484729, + -0.000406441415248947, 0.00032834991502413, 0.000359422093285086, 8.18895560425272e-05, + 0.000316835483508523, 0.000151442890664899}, + {-0.268764016434841, -0.275272048639511, 1.26239753050527, -0.000511224336925231, + 0.0095628568270856, -0.00397960092451418, 1.39587366293607e-05, 1.31409051361129e-05, + -9.83662017231755e-05, 1.87078667116619e-05}, + {27.168106989145, -2.43346872338192, 1.91135512970771, 0.0553180826818016, -0.0481878292619383, + 0.0052773235604729, -0.000428011927975304, 0.000528018208222772, -0.000285438191474895, + -5.71327627917386e-05}, + {-0.169494136517622, -0.350851545482921, 1.19922076033643, 0.0101120903675328, + -0.00151674465424115, 0.00548694086125656, -0.000108240000970513, 1.57202185024105e-05, + -9.77555098179959e-05, 2.09624089449761e-05}, + {-32.3807957489507, 1.8271436443167, 2.51530814328123, -0.0532334586403461, -0.0355980127727253, + -0.0213373892796204, 0.00045506092539885, 0.000545065581027688, 0.000141998709314758, + 0.000101051304611037}}; + susHandlingParameters.sus1coeffAlpha = { + {-27.6783250420482, -0.964805032861791, -0.503974297997131, -0.0446471081874084, + -0.048219538329297, 0.000958491361905381, -0.000290972187162876, -0.000657145721554176, + -0.000178087038629721, 4.09208968678946e-05}, + {2.24803085641869, 1.42938692406645, 0.30104994020693, 0.00756499999397385, 0.0117765927439368, + -0.000743685980641362, 4.69920803836194e-05, 0.000129815636957956, -9.10792250542345e-06, + -2.03870119873411e-05}, + {26.9943033817917, 0.147791175366868, -3.48256070200564, -0.0303332422478656, + 0.0183377266255394, 0.124593616125966, -0.000466003049304431, -0.000272000698791331, + -0.00063621309529853, -0.00158363678978767}, + {-0.221893380318465, 1.29919955307083, 0.21872487901019, 0.0049448219667127, + 0.00291224091529189, 0.00654651987282984, -9.86842469311185e-05, 8.20057454706638e-05, + 6.42331081725944e-05, 7.11656918299053e-05}, + {1.40178843964621, 1.1733111455249, 0.287485528779234, -0.000793970428759834, + 0.000170529273905818, -0.00268807864923086, 9.09553964483881e-05, -0.000271892733575409, + 8.52016306311741e-05, -0.000291797625433646}, + {0.65549617899457, 1.25716478394514, 0.301396415134214, -0.00357289640403958, + -0.000473416364133431, -0.010760332636205, -9.77220176481185e-05, 4.40798040046875e-05, + 2.84958344955681e-05, 0.000128583400693359}, + {6.20958048145025, 1.9528406481596, 1.32915657614139, -0.0326944423378284, -0.0158258335207969, + 0.0328249756354635, 0.00027113042931131, -0.000133980867173428, -0.000357964552318811, + 0.000224235061786191}, + {2.46222812180944, 1.1731834908026, 0.17440330925151, -0.00132279581980401, + -0.00447202005426964, -0.000804321602550913, -1.59526570766446e-05, 2.62946483533391e-05, + 3.28466749016414e-05, -6.63837547601294e-06}, + {42.615758859473, 2.46617281707273, -5.742515881283, -0.131942799763164, 0.20250702826603, + 0.0981562802911027, 0.00189939440077981, -0.0018591621618441, -0.00161121179693977, + -0.00058814458116749}}; + susHandlingParameters.sus1coeffBeta = { + {-12.300032617206, -1.06640894101328, 0.33950802247214, -0.00890867870617722, -0.04872758086642, + -0.0114263851027856, 0.000141061196404012, -0.000675469545483099, -0.000138249928781575, + -0.000138871036200597}, + {10.1631114109768, 0.261654603839785, 1.2376413405181, 0.00888558138614535, 0.00151674939001532, + -0.00534577602313027, 9.19430013005559e-05, 5.39804599087081e-05, -4.15760162347772e-05, + -7.60797902457032e-05}, + {-30.142329062199, 1.26939195100229, 6.14467186367471, 0.0464163689935328, 0.00379001947505376, + -0.165444163648109, 0.000516545385538741, 1.56053219154647e-05, -5.58651971370719e-05, + 0.00173185063955313}, + {12.1454103989862, -0.243589095509132, 2.02543716988677, -0.000857989774598331, + -0.00705278543432513, 0.0250580538307654, 3.50683653081847e-05, -2.63093897408875e-05, + -5.67352645830913e-05, 0.000232270832022029}, + {4.4338108906594, -0.305276965994378, 1.17293558142526, 0.000152618994429577, + 0.00134432642920902, -0.00104036813342885, 0.000334476082056995, 6.74826804343671e-05, + 0.000275311897725414, 7.58157740577916e-05}, + {3.47680700379043, -0.154163381023597, 1.389579838768, 0.000799705880026268, + 0.00401980026462874, -0.00915311817354667, -2.54817301605075e-06, -2.27422984169921e-05, + -2.61224817848938e-05, 6.00381132540332e-05}, + {29.469181543703, -0.722888948550437, 3.3623377135197, 0.00148445490093232, -0.0474780142430845, + 0.0486755575785462, 0.000126295091963757, 0.000526632230895258, -0.000259305985126003, + 0.000412751148048724}, + {2.67029041722834, -0.0837968038501666, 1.37628504937018, 0.00165061312885753, + -0.00953813055064273, 0.0032433005486936, -1.6522452172598e-05, 0.000144574078261271, + -8.47348746872376e-05, -1.92509604512729e-06}, + {-20.959201441285, -2.23605897639125, 5.73044624806043, 0.0354141964763815, 0.0887545371234514, + -0.193862330062381, 0.000216532998121618, -0.00207707610520973, 0.000552928905346826, + 0.00190182163597828}}; + susHandlingParameters.sus2coeffAlpha = { + {6.51602979328333, 0.690575501042577, 1.18185457002269, -0.0153161662266588, + 0.00145972227341484, 0.0351496474730776, -0.000172645571366945, -6.04213053580018e-05, + 9.74494676304114e-05, 0.000334122888261002}, + {0.954398509323963, 1.10996214782069, 0.313314231563221, -0.00367553051112208, + 0.0110290193380194, 0.000240079475656232, -6.93444423181303e-05, 0.000107433381295167, + 1.30750132315838e-05, -2.43580795300515e-05}, + {-55.1159841655056, -1.47449655191106, 3.40106264596874, -0.0621428271456258, + 0.0659788065633613, -0.0791732068323335, -0.000524264070592741, 0.000582093651418709, + -0.000586102213707195, 0.000658133691098817}, + {1.98614148820353, 1.32058724763677, 0.156843003413303, 0.002748082456053, 0.00202677073171519, + 0.00382360695862248, -0.000122364309010211, 5.33354637965168e-05, 3.93641210098335e-05, + 4.06398431916703e-05}, + {3.41223117010734, 1.1597568029329, 0.31881674291653, -0.000382400010917784, + -0.000754945672515052, -0.00079200882313927, 0.000145713118224563, -0.00026910957285589, + 0.000137876961532787, -0.000326798596746712}, + {6.23333031852853, 1.24902998148103, -0.0162317540018123, -0.00338184464699201, + 0.000420329743164687, 0.00202038442335185, -7.10435889754986e-05, -6.04039458988991e-06, + 7.25318569569788e-06, -2.5930447720704e-05}, + {191.759784636909, -10.5228276216193, 8.48306234734519, 0.243240262512846, -0.344226468125615, + 0.126267158197535, -0.00186612281541009, 0.00304415728817747, -0.00304958575196089, + 0.000457236034569107}, + {5.61375025356727, 1.1692295110657, 0.224665256727786, -0.00230481633344849, + -0.00746693012026367, -0.00172583925345173, -7.00823444553058e-06, 7.31362778266959e-05, + 5.81988007269583e-05, 1.3723604109425e-05}, + {98.0250669452855, -2.18500123986039, -6.68238707939385, 0.000754807832106659, + 0.256133336978808, 0.110826583415768, 0.000457663127670018, -0.00197655629847616, + -0.00254305206375073, -0.000466731538082995}}; + susHandlingParameters.sus2coeffBeta = { + {41.1102358678699, 2.3034699186519, 2.74551448799899, 0.061701310929235, 0.0317074142089495, + 0.0308171492962288, 0.00049453042200054, 0.000519222896270701, 2.85420168881716e-05, + 0.000259197384126413}, + {4.46821725251333, 0.0125273331991983, 1.32640678842532, 0.000543566569079156, + 0.00396616601484022, -0.00488408099728387, -3.05734704054868e-06, 7.3424831303621e-05, + -5.49439160235527e-05, -8.30708110469922e-05}, + {64.773396165255, 2.97057686090134, -1.90770757709096, 0.062747116236773, -0.077990648565002, + 0.0613989204238974, 0.00055512113297293, -0.000347045533958329, 0.00104059576098392, + -0.000348638726253297}, + {3.10352939390402, -0.2376108554276, 1.60523925160222, 0.00116454605680723, -0.0067958260462381, + 0.0136561370875238, 2.59929059167486e-05, 3.33825895937897e-05, -5.55828531601728e-05, + 0.000109833374761172}, + {0.156052891975873, -0.320721597024578, 1.15208488414874, 0.00164743688819939, + 0.000534718891498932, 0.000469870758457642, 0.000308432468885207, 0.00011789470679678, + 0.000292373398965513, 0.000183599033441813}, + {2.84967971406268, -0.21374251183113, 1.09938586447269, 2.34894704600407e-05, + 0.00588345375399262, 0.00296966835738407, 8.42707308834155e-06, 2.81870099202641e-06, + -3.56732787246631e-05, -7.04534663356379e-05}, + {-7.59892007483895, 0.358662160515702, 0.805137646978357, 0.00222144376998348, + 0.0464438387809707, 0.00847551828841782, 3.24805702347551e-05, 5.45500807838332e-05, + 0.000941378089367713, 0.000353137737023192}, + {-4.65367165487109, 0.201306010390421, 1.19135575710523, -0.00692801521395975, + 0.00394118754078443, 0.00426360093528599, 6.297683536736e-05, -7.15794236895102e-05, + -7.47076172176468e-05, -1.94516917836346e-05}, + {-59.5882618930651, 3.84530212586425, 3.50497032358686, -0.116100453177197, -0.0380997421813177, + -0.0581898335691109, 0.00111464935006159, 0.000559313074537689, 0.000168067749764069, + 0.000563224178849256}}; + susHandlingParameters.sus3coeffAlpha = { + {-174.687021034355, -7.53454036765748, -9.33798316371397, -0.18212338430986, -0.242523652239734, + -0.202086838965846, -0.00138648793335223, -0.00225430176012882, -0.00198887215340364, + -0.00160678535160774}, + {6.92009692410602, 1.8192037428209, 0.254908171908415, 0.0179273243472017, 0.00894059238779664, + -0.000436952529644, 0.000138070523903458, 9.22759645920339e-05, -9.4312261303588e-06, + -1.76647897892869e-05}, + {-17.9720006944368, 0.230510201259892, 1.10751755772907, -0.00973621304161327, + 0.0554450499198677, -0.00590970792122449, -2.92393772526592e-05, 0.000444329929586969, + -0.000436055839773919, -9.5869891049503e-05}, + {-4.9880829382985, 1.33627775121504, -0.330382157073243, 0.00306744056311184, + 0.00376353074674973, -0.0107453978169225, -0.00010680477021693, 5.17225535432745e-05, + 7.4423443938376e-05, -0.000107927900087035}, + {0.952867982900728, 1.14513280899596, 0.307744203675505, 0.000404669974219378, + -0.000737988606997615, 0.00120218232577844, 0.000191147653645603, -0.000275058867995882, + 0.000137187356620739, -0.000320202731145004}, + {8.076706574364, 1.31338618710295, -0.334634356394277, -0.00209719438033295, + -0.00381753503582303, 0.0100347823323616, -7.00550548221671e-05, -1.97626956996069e-05, + 7.80079707003333e-05, -8.95904360920744e-05}, + {-82.4748312650249, 8.63074484663009, -0.949295700187556, -0.178618807265278, 0.130143669167547, + 0.0284326533865768, 0.00149831261351137, -0.0011583692969717, 0.0010560778729661, + 0.000635404380970666}, + {3.34457857521978, 1.09242517408071, 0.241722402244944, 0.00381629887587041, + -0.00863580122530851, 0.00137050492069702, -8.91046701171713e-05, 8.44169683308007e-05, + -3.54608413548779e-05, 8.54042677832451e-06}, + {78.1540457908649, -1.30266922193303, -5.33605443700115, 0.0184226131926499, 0.146629920899062, + 0.110698519952472, 6.64041537651749e-05, -0.00120174584530713, -0.00133177694921411, + -0.000796422644338886}}; + susHandlingParameters.sus3coeffBeta = { + {-31.5704266802979, -5.10700699133189, 2.84549700473812, -0.122701561048957, -0.11257100034746, + 0.102120576206517, -0.000796645106694696, -0.00192211266325167, -4.99981232866237e-05, + 0.00104036677004523}, + {-0.734294938181273, -0.0694317595592039, 1.34746975389878, -0.00103465544451119, + 0.00389798465946559, -0.00308561832194191, -2.91843250099708e-06, 7.59634622232999e-05, + -6.54571602919161e-05, -0.000104146832644606}, + {24.2649069708536, 3.08145095664586, 1.88975821636026, 0.0767528234206466, -0.0526971951753399, + -0.0477053831942802, 0.000613806533422364, -0.000631628059238499, 0.00026217621127941, + 0.000555307997961608}, + {0.62884078560034, -0.152668817824194, 1.70304497205574, 0.000894387499536142, + -0.00306495168098874, 0.0180087418010658, 1.74990847586174e-05, 3.1263263531046e-05, + -7.1643235604579e-06, 0.000147876621100347}, + {-3.05400297018165, -0.316256447664344, 1.14841722699638, 0.000671621084688467, + -0.000906765726598906, 0.000687041032077189, 0.000323419818039841, 0.000128019308781935, + 0.000286018723737538, 0.000192248693306256}, + {-4.39855066935163, -0.322858945262125, 1.44405016355615, -4.93181749911261e-05, + 0.0127396834052722, -0.00523149676786941, 2.56561922352657e-05, 7.61202764874326e-06, + -0.00014623717850039, 8.12219846932013e-06}, + {110.820397525173, -10.9497307382094, 2.48939759290446, 0.296585618718034, -0.142611297893517, + -0.0141810186612052, -0.00275127095595919, 0.00160686698368569, -0.000872029428758877, + -0.000410522437887563}, + {-7.15740446281205, 0.104233532313688, 1.13155893729292, -0.00350418544400852, + 0.00532058598508803, 0.00459314980222008, 3.09155436939349e-05, -7.60935741692174e-05, + -5.87922606348196e-05, 2.56146268588382e-05}, + {44.8818060495112, -7.94729992210875, 3.59286389225051, 0.217944601088562, 0.108087933176612, + -0.116711715153385, -0.00194260120960441, -0.0015752762498594, -0.000331129410732722, + 0.00125896996438418}}; + susHandlingParameters.sus4coeffAlpha = { + {-12.4581187126738, 0.398038572289047, -0.438887880988151, -0.00965382887938283, + -0.0309322349328842, -0.00359106522420111, -7.79546112299913e-06, -0.000432733997178497, + -9.79031907635314e-05, -1.49299384451257e-05}, + {8.41054378583447, 1.87462327360707, 0.266809999719952, 0.0216455385250676, 0.00879426079919981, + -0.00142295319820553, 0.000194819780653264, 8.57549705064449e-05, -3.56478452552367e-05, + -1.65680920554434e-05}, + {16.4141780945815, 2.57697842088604, 0.373972171754278, 0.0498264199400303, 0.0183175817756131, + -0.008545409848878, 0.000422696533006382, -0.000268245978898508, -0.000663188021815416, + -7.51144017137827e-05}, + {0.796692054977593, 1.26773229735266, 0.247715261673662, 0.00358183885438128, + 0.00216435175662881, 0.00713732829335305, -0.000110129715615857, 3.56051594182427e-05, + 5.03074365340535e-05, 8.40279146176271e-05}, + {2.37491588500165, 1.05997969088519, 0.309540461340971, -0.000405047711742513, + 0.000462224730316111, -0.00201887171945793, 0.000260159805167265, -0.000282867209803598, + 0.000201613303652666, -0.000277796442847579}, + {6.36749007598708, 1.31659760017973, -0.122724934153231, -0.00328808937096891, + -0.00577347207798776, 0.00403172074457999, -7.45676459772001e-05, 1.79838644222274e-05, + 0.000104552066440564, -2.78115121929346e-05}, + {-47.9667098848496, 3.97703197139796, -1.96403894754299, -0.0577989657406978, + 0.0634225576208007, -0.0346023445055141, 0.00045886475369098, -0.000326132951996844, + 0.000716490441845967, -0.000136132038635483}, + {6.21505474256094, 0.871830486201601, 0.286906473833627, 0.007875292606045, + -0.00974634725746389, 0.00128416935792136, -0.000111796743751489, 0.000102016719989187, + -3.3503088289589e-05, -1.03874407813931e-05}, + {102.09801265482, -4.12715152309748, -5.04594403360339, 0.075499959116996, 0.216574192561683, + 0.0750031215784663, -0.000147358932612646, -0.0023710703422108, -0.00143310719642393, + -0.000431914403446768}}; + susHandlingParameters.sus4coeffBeta = { + {-21.5077132684032, -1.60004839699939, -0.0298995033958561, -0.0315563250430659, + -0.0424403625879891, -0.0245426225510417, -0.000209861203016225, -0.000422150973104431, + -0.00030514398458781, -0.000211986731019738}, + {9.07644247897601, 0.207457289788099, 1.26735366597312, 0.00768477352180427, + 0.00429230749575816, -0.00514802326062087, 7.56149591998578e-05, 8.42794730840662e-05, + -3.62215715492783e-05, -5.24384190165239e-05}, + {-33.5225408043693, -3.11167857248829, 1.91760591695775, -0.0963752386435729, + 0.00026620241534153, -0.0256680391021823, -0.00102188712837393, 2.63753563968978e-05, + 0.000113172463974702, 0.000271939918507175}, + {19.1379025029401, -0.225979661987912, 2.72337120022998, -0.00136982412154458, + -0.00447301210555274, 0.046496718064139, 2.09123846958985e-05, -4.30383094864847e-05, + -1.22808643520768e-05, 0.000440555709696048}, + {2.957867714783, -0.316069593806939, 1.06379930645214, 0.00103244713047271, 0.00148059212230411, + 0.000557885068990542, 0.000288633931072557, 0.000172775380291659, 0.000269738457990237, + 0.000254577019084984}, + {2.04155199929521, -0.318303488378033, 1.37820715117028, 0.00114788656817743, + 0.0130051117909245, -0.00743109928493789, 1.22403390396844e-05, -3.19245785131217e-05, + -0.000156735218010879, 3.81458400945988e-05}, + {27.314954181241, -1.43916155634084, 2.48967706992348, 0.0278695408478388, -0.0341141456915131, + 0.0281959785297513, -0.000252996164135396, 0.000163365679366542, -0.000380129463154642, + 0.000159350154429114}, + {-0.274693278266294, 0.0199711721436635, 1.26676843352524, -0.0006713759238817, + -0.00389715205101059, 0.00294298337610857, -9.58643121413979e-06, 6.30700938550725e-05, + -6.07188867796123e-05, 7.72199861279611e-06}, + {-74.1601853968901, 2.55641628908672, 6.38533530714782, -0.0582345132980647, + -0.0653804553172819, -0.138850555683872, 0.000489364157827405, 0.000469559629292745, + 0.000698140692952438, 0.00123017528239406}}; + susHandlingParameters.sus5coeffAlpha = { + {-12.1398741236355, 1.99425442858125, -1.9303044815802, 0.0418421279520049, -0.0309683799946315, + -0.0562201123081437, 0.000522607299552916, -0.000375386573815007, -0.000183899715035788, + -0.000600349486293698}, + {4.51862054729553, 1.72396080253297, 0.274562680698765, 0.0162681383591035, 0.0108410181586673, + -0.000272215427359511, 0.000124164068046579, 0.000125586897851351, -1.24082224214974e-05, + -1.63339067540159e-05}, + {63.0100748193658, 7.78014670478172, 0.327263471268564, 0.181264302704374, -0.0652454854214506, + -0.03906716801285, 0.00166924078925478, -0.000749939315526625, 0.000320696101132374, + 0.000499934751180042}, + {-2.14377722994325, 1.33617641673436, 0.0973465660282871, 0.00389526886867845, + 0.00526064997381395, 0.00244964888333519, -8.59416490903541e-05, 4.58871931007681e-05, + 8.6123353128647e-05, 2.85447259858337e-05}, + {0.164792977301912, 1.17541977248641, 0.348838798760518, -0.000180865118417534, + 0.000331789515553421, -0.000734333865631793, 9.76677859410759e-05, -0.000324347075049525, + 8.66683396011167e-05, -0.000385839566009832}, + {-0.228934187493575, 1.30552820143752, 0.306779576899158, -0.00508763741184706, + -0.00318524263093038, -0.00878095392529144, -6.59040013073836e-05, 8.69122529321691e-05, + 5.73853071731283e-05, 8.56628414466758e-05}, + {22.6047744510684, -0.591739857860868, 0.566728856847393, 0.0498124268150265, + -0.0214126910277926, 0.00538091942017912, -0.000391517685229849, 0.000554321668236216, + 0.000191004410219065, 0.000102775124022018}, + {4.54704081104052, 0.844841244606025, 0.181355971462193, 0.0109743851006749, + -0.00363467884122547, 0.00108873046814694, -0.000153236888951059, 3.14623342713789e-06, + -2.78503202185463e-05, 3.99983788680736e-06}, + {-30.878359404848, 5.20536009886854, -0.674455093700773, -0.10801865891189, -0.0514805639475938, + 0.0503660452068572, 0.00072776817295273, 0.00120288537038655, -0.000301602375634166, + -0.000477098479809266}}; + susHandlingParameters.sus5coeffBeta = { + {16.8155737032787, 0.65475660868259, 1.95532810363711, 0.000295624718662669, 0.0426379914736747, + 0.00192544771588337, -4.94534888281508e-05, 8.32299142575155e-05, 0.000645497238623369, + -0.000234155227840799}, + {9.48268090632318, 0.528942263930744, 1.34030963800712, 0.0173605129814363, 0.00581086655972212, + -0.00365006277801141, 0.000180048140973223, 0.000102002650672644, -4.10833110241736e-05, + -8.7810396165556e-05}, + {-47.8325489165383, -4.78262055949503, 1.66912859871505, -0.143518014673292, 0.0288441527062856, + -0.00322823115861497, -0.00148509910480755, 0.000284265179004289, -0.000175299737313045, + -7.04175618676909e-05}, + {3.70510151312723, -0.272200626024415, 1.5527519845099, 0.000589727630962265, + -0.00889682554869096, 0.0109857452472628, 3.05876215574877e-05, 2.09194236165814e-05, + -8.33769024439277e-05, 6.90991113575066e-05}, + {0.820199776906695, -0.355683467192776, 1.17142130858009, -0.000160174871610729, + 4.09723480153701e-05, 0.000209103751629257, 0.000390331989170637, 6.45642836249667e-05, + 0.000318092703362044, 0.000107158633760141}, + {5.52084497768914, -0.227775345312466, 0.845897282556327, 0.00157426476122436, + 0.00657189797805861, 0.0103797665963117, 2.51479848048895e-05, -4.78371400399983e-05, + -5.20221896473413e-05, -0.000143840492906166}, + {-33.4875689683454, 0.937557276329106, -1.02741065470967, -0.0140023273976314, + 0.0401908729477037, -0.0512457211360142, 7.05537967426573e-05, -0.00027521752411122, + 0.000407657552700476, -0.000458411000693613}, + {0.931346887326171, -0.320804452025793, 1.28866325376154, 0.00912456151698805, + -0.00404367403569981, 0.00477543659981282, -9.43987917474817e-05, 4.66464249533497e-05, + -7.89362487264572e-05, -1.0951496495443e-05}, + {-38.3689359928435, 3.8540516906071, 1.26391725545116, -0.108584643500539, -0.0542697403292778, + 0.0285360568428252, 0.000845084580479371, 0.00114184315411245, -0.000169538153750085, + -0.000336529204350355}}; + susHandlingParameters.sus6coeffAlpha = { + {13.0465222152293, 0.0639132159808454, 2.98083557560227, -0.0773202212713293, + 0.0949075412003712, 0.0503055998355815, -0.00104133434256204, 0.000633099036136146, + 0.00091428505258307, 0.000259857066722932}, + {1.66740227859888, 1.55804368674744, 0.209274741749388, 0.0123798418560859, 0.00724950517167516, + -0.000577445375457582, 8.94374551545955e-05, 6.94513586221567e-05, -1.06065583714065e-05, + -1.43899892666699e-05}, + {8.71610925597519, 1.42112818752419, -0.549859300501301, 0.0374581774684577, 0.0617635595955198, + 0.0447491072679598, 0.00069998577106559, 0.00101018723225412, -4.88501228194031e-06, + -0.000434861113274231}, + {-2.3555601314395, 1.29430213886389, 0.179499593411187, 0.00440896450927253, + 0.00352052300927628, 0.00434187143967281, -9.66615195654703e-05, 3.64923075694275e-05, + 6.09619017310129e-05, 4.23908862836885e-05}, + {-0.858019663974047, 1.10138705956076, 0.278789852526915, -0.000199798507752607, + 0.00112092406838628, -0.00177346866231588, 0.000217816070307086, -0.000240713988238257, + 0.000150795563555828, -0.000279246491927943}, + {7.93661480471297, 1.33902098855997, -0.64010306493848, -0.00307944184518557, + -0.00511421127083497, 0.0204008636376403, -9.50042323904954e-05, 6.01530207062221e-05, + 9.13233708460098e-05, -0.000206717750924323}, + {16.2658124154565, 0.191301571705827, 1.02390350838635, 0.0258487436355216, -0.0219752092833362, + 0.0236916776412211, -0.000350496453661261, -0.000123849795280597, -0.000532190902882765, + 9.36018171121253e-05}, + {-1.53023612303052, 1.29132951637076, 0.181159073530008, -0.0023490608317645, + -0.00370741703297037, -0.000229071300377431, -1.6634455407558e-05, 1.11387154630828e-05, + 1.02609175615251e-05, -9.64717658954667e-06}, + {-32.9918791079688, 0.093536793089853, 4.76858627395571, 0.0595845684553358, -0.054845749101257, + -0.133247382500001, -0.000688999201915199, 7.67286265747961e-05, 0.000868163357631254, + 0.00120099606910313}}; + susHandlingParameters.sus6coeffBeta = { + {12.7380220453847, -0.6087309901836, 2.60957722462363, -0.0415319939920917, 0.0444944768824276, + 0.0223231464060241, -0.000421503508733887, -9.39560038638717e-05, 0.000821479971871302, + -4.5330528329465e-05}, + {1.96846333975847, -0.33921438143463, 1.23957110477613, -0.00948832495296823, + 0.00107211134687287, -0.00410820045700199, -9.33679611473279e-05, 3.72984782145427e-05, + -4.04514487800062e-05, -7.6296149087237e-05}, + {5.7454444934481, -1.58476383793609, -0.418479494289251, -0.0985177320630941, + -0.0862179276808015, 0.0126762052037897, -0.00118207758271301, -0.000190361442918412, + 0.0011723869613426, 0.000122882034141316}, + {2.11042287406433, -0.225942746245056, 1.18084080712528, -0.00103013931607172, + -0.00675606790663387, -0.00106646109062746, 1.7708839355979e-05, -3.13642668374253e-05, + -5.87601932564404e-05, -3.92033314627704e-05}, + {2.96049248725882, -0.286261455028255, 1.09122556181319, -0.000672369023155898, + 0.000574446975796023, 0.000120303729680796, 0.000292285799270644, 0.000170497873487264, + 0.000259925974231328, 0.000222437797823852}, + {1.65218061201483, -0.19535446105784, 1.39609640918411, 0.000961524354787167, + 0.00592400381724333, -0.0078500192096718, -7.02791628080906e-07, -2.07197580883822e-05, + -4.33518182614169e-05, 4.66993119419691e-05}, + {-19.56673237415, 1.06558565338761, 0.151160448373445, -0.0252628659378108, 0.0281230551050938, + -0.0217328869907185, 0.000241309440918385, -0.000116449585258429, 0.000401546410974577, + -0.000147563886502726}, + {1.56167171538684, -0.155299366654736, 1.20084049723279, 0.00457348893890231, + 0.00118888040006052, 0.0029920178735941, -5.583448120596e-05, -2.34496315691865e-05, + -5.3309466243918e-05, 6.20289310356821e-06}, + {1.95050549495182, -2.74909818412705, 3.80268788018641, 0.0629242254381785, 0.0581479035315726, + -0.111361283351269, -0.00047845777495158, -0.00075354297736741, -0.000186887396585446, + 0.00119710704771344}}; + susHandlingParameters.sus7coeffAlpha = { + {-92.1126183408754, -3.77261746189525, -4.50604668349213, -0.0909560776043523, + -0.15646903318971, -0.0766293642415356, -0.00059452135473577, -0.00144790037129283, + -0.00119021101127241, -0.000460110780350978}, + {1.60822506792345, 1.12993931449931, 0.300781032865641, -0.00405149856360946, + 0.0116663280665617, -0.000746071920075153, -8.36092173253351e-05, 0.000126762041147563, + -1.57820750462019e-05, -2.13840141586661e-05}, + {-151.403952985468, -5.77049222793992, 9.71132757422642, -0.113259116970462, 0.284142453949027, + -0.198625061659164, -0.000836450164210354, 0.00174062771509636, -0.00323746390757859, + 0.00124721932086258}, + {3.47391964888809, 1.28788318973591, 0.358380140281919, 0.0033863520864927, 0.00154601909793475, + 0.0103457296050314, -9.56426572270873e-05, 5.48838958555808e-05, 2.97537427220847e-05, + 0.000104735911514185}, + {3.32650947866065, 1.16701012685798, 0.293514063672376, -0.00065850791542434, + -8.61746510464303e-05, -0.00212038990772211, 0.00010377123197, -0.000262818127593837, + 0.000103360882478383, -0.000296739688930329}, + {-0.440176043435378, 1.18923278867097, 0.519516382652818, -0.00138846714677511, + 0.00266491699926247, -0.014254675949624, -4.20279929822439e-05, -5.49260281515447e-05, + -1.00328708454487e-05, 0.000138142092498215}, + {9.54962966738358, 1.83809145920811, 1.82162819067959, -0.0116786627338505, + -0.00496037444422313, 0.0590883547819332, 7.48465315787857e-05, 0.000221693951602584, + 7.96466345174136e-06, 0.000638822537725177}, + {7.04862901290925, 0.876813777672465, 0.16368093989381, 0.00928717461441627, + -0.00276538956293246, 0.00117995419940653, -0.000141511492474493, -6.09796031786385e-06, + -2.62114930414747e-05, -2.88713611443788e-06}, + {135.349147631811, -7.21933296299596, -6.02379024934871, 0.19557354282067, 0.207680233512614, + 0.12880101618361, -0.00169832076532024, -0.00192216719797732, -0.00188763612041332, + -0.00103101801961442}}; + susHandlingParameters.sus7coeffBeta = { + {-12.7115487367622, -1.08890790360556, 0.0579616268854079, -0.0212303293514951, + -0.0395948453851818, -0.0275564242614342, -0.000228652851842222, -0.000148106159109458, + -0.000555136649469199, -0.000198260004582737}, + {-0.988147625946871, -0.759018567468546, 1.20998292002818, -0.0241231836977845, + -0.000572110443300516, -0.00294835038249426, -0.00026533039022186, 6.82250069765274e-06, + 7.21038415209318e-06, -6.54881435118179e-05}, + {98.0979345921564, 4.27381413621355, -4.39956005193548, 0.0709109587666745, -0.172774236139236, + 0.107243391488741, 0.000421832640471043, -0.00140450884710288, 0.00158019019392239, + -0.00078512547169536}, + {4.10892685652543, -0.229301778557857, 1.33380992987117, -0.000250095848720304, + -0.00555205065514645, 0.00355052914398176, 1.62727119770752e-05, -1.26026527654764e-05, + -3.25505031810898e-05, 5.79970895921158e-06}, + {3.09432502337258, -0.300556003790433, 1.17085811008124, 0.00128679594824324, + 0.00148229981422985, 9.15267474159147e-05, 0.000300497843413856, 6.31378865575566e-05, + 0.000258447032558814, 9.79142983264352e-05}, + {8.92336134924575, -0.197306981784312, 0.659908505354084, 0.00175572239373996, + 0.006801023678097, 0.0189775987436792, 9.2187857727721e-06, -4.8706332690626e-05, + -6.887009887486e-05, -0.000266455617735054}, + {-52.0734887320227, 2.64822385560272, -1.72387600304694, -0.0383944891609251, 0.110873671161269, + -0.0475247245070445, 0.000194652401328063, -0.000697307928990137, 0.00124021816001, + -0.000194213899980878}, + {2.08203985879155, -0.127503525368396, 1.17628056094647, 0.00283288065938444, + 0.00394668214608305, 0.00314868636161131, -2.99504350569853e-05, -7.11070816314279e-05, + -6.30148122529749e-05, 2.28114298989664e-05}, + {191.321181158032, -12.2449557187473, -7.21933741885107, 0.267954293388644, 0.331529493933124, + 0.149867703984027, -0.00222279201444128, -0.00284724570619954, -0.00298774060233964, + -0.000988903783752156}}; + susHandlingParameters.sus8coeffAlpha = { + {5.46354311880959, 1.15370126035432, 0.568432485840475, -0.00105094692478431, + -0.000472899673842554, 0.015581320536192, 2.26460844314248e-05, -0.000254397947062058, + 0.000198938007250408, 0.000102026690279006}, + {8.8976133108173, 1.89502416095352, 0.268670471819199, 0.0217013413241972, 0.00973925295182384, + -0.00116357269193765, 0.000185865842232419, 0.000103311614912702, -2.46539447920969e-05, + -2.06292928734686e-05}, + {-45.4550803910752, 1.27220123406993, 5.21483855848504, 0.0315791081623634, 0.0725172355124129, + -0.13947591535243, 0.000412577580637848, 0.000434545096994917, -0.000840043932292312, + 0.00126857487044307}, + {1.81302768546433, 1.20563501267535, 0.344815267182167, 0.00546879453241056, + -0.00115382996865884, 0.010597876132341, -7.75885604486581e-05, 8.99568815949154e-05, + -2.98129544974679e-06, 0.000108913239345604}, + {2.19111439539173, 1.06951675598148, 0.283707798607213, 0.00016478588207518, + 0.000196086067268121, -0.00214980231173703, 0.000237820475654357, -0.000256402967908595, + 0.000165966620658577, -0.000268394081675921}, + {15.0858674915897, 1.27922724811168, -1.0803137812576, -0.00184009775302466, + -0.00458792284209219, 0.0359393555418547, -6.05121024079603e-05, -1.2288384024143e-05, + 8.55484605384438e-05, -0.000379241348638065}, + {-14.9594190080906, 1.79473182195746, -1.00830704063572, 0.000890685410857856, + 0.0408932029176081, -0.0165460857151619, -0.000170544299916973, -0.000370901607010145, + 0.000324089709129097, -9.33010240878062e-05}, + {0.867614491733251, 1.38248194737027, 0.233408537422123, -0.00772942878114575, + -0.00783126068079782, -0.000413713955432221, 4.5775750146291e-05, 6.97323029940275e-05, + 1.70664456940787e-05, 6.75517901233086e-06}, + {2.34474364146174, -0.777275400251477, 2.09531381577911, 0.0170780716714389, 0.102855060371092, + -0.1203441505925, 0.000187004964420911, -0.00141720441050986, -0.000336251285258365, + 0.00145175125888695}}; + susHandlingParameters.sus8coeffBeta = { + {28.3033101237397, 1.77504446792811, 1.70758838986317, 0.0307800697044683, 0.0598759344275936, + -0.014461432284373, 0.000128415617799076, 0.000664419128546701, 0.000312923304130995, + -0.000269026446641855}, + {7.73040563051023, 0.0267291479555493, 1.16189582308493, 0.000611047892976521, + -0.00213680506915073, -0.00517435586596902, -3.60304406049766e-06, -1.74452976404459e-05, + -3.95396925228538e-05, -7.01948519410633e-05}, + {-48.0766126130725, -3.77981206700298, 3.03482861087335, -0.0678496412519532, 0.115260678424016, + -0.0109681510065038, -0.000438011443691466, 0.00097230136258486, -0.000930875177732769, + -0.000203144239955507}, + {12.1881935626341, -0.234345089308583, 2.01134619426134, 0.000181529284001169, + -0.00642848065105061, 0.0243985799415726, 2.0224042581776e-05, 5.22503286757285e-06, + -4.75196303016323e-05, 0.000221160482364556}, + {3.49559433498742, -0.294995112674766, 1.07892379698257, 0.000861664794052587, + 0.00138978933062055, 0.000436385106465176, 0.000288095124755908, 0.000147259769247883, + 0.000256686898599516, 0.000198982412957039}, + {9.36663996178607, -0.171266136751803, 0.799869891484541, -0.000896305696610864, + 0.00477919972789653, 0.0077876110326094, 9.16475263625076e-06, 3.02461250100473e-05, + -3.63917701783264e-05, -0.000101376940843402}, + {9.93372683055145, 1.02056557854246, 3.01635426591734, -0.0477113881140277, -0.0280426434406976, + 0.0438813017696874, 0.000470431190169998, -7.55753674679743e-05, -0.000516444906323815, + 0.000253844418223843}, + {4.12868774589741, -0.305711790187688, 1.15739216407191, 0.00942395115281056, + 0.00264758462357433, 0.00227985850688479, -0.000107537164019682, -4.91396736189963e-05, + -5.3803493814502e-05, 6.80587059728718e-06}, + {64.9193383444005, -1.57724255547465, -3.82166532626293, 0.0104712238987591, 0.0898786950946473, + 0.128910456296131, -8.27123227422217e-05, -0.000143979624107479, -0.00146684876653306, + -0.00102226799570239}}; + susHandlingParameters.sus9coeffAlpha = { + {65.8975109449121, 2.19115342242175, 6.11069527811832, -0.0219884864133703, 0.119985456538482, + 0.142746712551924, -0.000465882328687976, 0.000606525132125852, 0.00141667074621881, + 0.00109715845894006}, + {5.70337356029945, 1.86705636976809, 0.235584190291708, 0.0194937327615426, 0.00973291465247784, + -0.00155675297510773, 0.000147099297988423, 0.000115708967219349, -4.1462310493722e-05, + -9.80097031103588e-06}, + {138.221145997284, 6.07665575619595, -9.08085914250542, 0.0839801072927519, -0.143071750033303, + 0.237868300719915, 0.000626693630444932, -0.000579788170871402, 0.00181740650944343, + -0.00207086879728281}, + {-7.78295582666151, 1.37506685179192, -0.507596181420042, 0.00350118305456038, + 0.00380814310115541, -0.0174012437563343, -0.000124801268056815, 2.96314830184492e-05, + 6.3416992450033e-05, -0.000190177262510221}, + {0.13102597129751, 1.24228303845143, 0.328808873447393, 2.6858679536165e-05, + 0.000231428138164498, -0.000584089095259736, 5.5322167970451e-05, -0.000322205709821716, + 7.71348293209208e-05, -0.000393885990364776}, + {4.64571633968935, 1.2668223691397, -0.158952088650432, -0.0038344859267428, 0.0030051503726095, + 0.00455578826025588, -9.42520993914957e-05, 5.81633314412289e-05, -4.43545804544095e-05, + -4.83524454851519e-05}, + {99.2385930314563, -3.65569343617926, 5.54203926675588, 0.0975630395981933, -0.15701634159692, + 0.107834711298836, -0.000885326636237814, 0.000960753844480462, -0.00179894024848343, + 0.000583066757644971}, + {2.82671549736619, 1.11214198870501, 0.214735318432744, 0.00284415167563662, + -0.00743289575690122, 0.000382705440762292, -7.43232442872501e-05, 6.96994098083348e-05, + -4.15108111710131e-06, 1.33520085213482e-05}, + {36.9013743125415, -0.522392401546163, -1.52452843963663, 0.0261375433218879, 0.060573568610239, + 0.0182582125221054, -0.000244373383911157, -0.000271385147292484, -0.000723799969427732, + 6.76324880239196e-05}}; + susHandlingParameters.sus9coeffBeta = { + {128.70886435409, 7.27355509732751, 7.18142203531244, 0.1536100459329, 0.199455846541636, + 0.101824964939793, 0.00116666116789421, 0.00181595584079788, 0.00159271319494017, + 0.000556768406475719}, + {-7.07933839681024, -0.979062424441878, 1.21792546815617, -0.0295740143783226, + -0.00442780611714201, -0.00329612819203176, -0.000291373125216143, -7.47259350176359e-05, + -4.87265282482212e-05, -7.87490350444332e-05}, + {41.1357193180502, 2.75138456414254, -0.0160889117718198, 0.0274001112562423, + -0.145644717742057, -0.0316076203283094, -0.000136443337244472, -0.00153945199081365, + 0.000938960439977633, 0.000599987111822885}, + {2.7980384746608, -0.234741037383589, 1.5342193016705, -0.000993791566721689, + -0.00787533639513478, 0.00927468655141365, 2.63308697896639e-05, -3.42816267184975e-05, + -8.48879419798771e-05, 3.84043821333798e-05}, + {0.427687530667804, -0.346076633694936, 1.22968527483851, -4.95098138311122e-05, + 0.000298245372198029, 0.000332756250024796, 0.00040375986210644, 5.20675972504572e-05, + 0.000327042170278218, 5.93011568264671e-05}, + {4.50337810133314, -0.279364254817202, 0.945812187846199, 0.000116182663432306, + 0.0115646046622083, 0.00908289960302886, 1.90394667311541e-05, -4.4360223646434e-06, + -0.000131398914898614, -0.000145568992865512}, + {-36.3377213654193, 2.21047221783626, 0.0609982245149821, -0.0670546774988572, + 0.016827777144747, -0.0277834084058314, 0.000778301409125556, 0.000135846745194401, + 0.00043261858797068, -0.00021172728254561}, + {-0.737678205841529, -0.217352122193475, 1.23494846329297, 0.00748173441779792, + 0.0019595873704705, 0.00567253723266176, -8.34768773292938e-05, -3.50608394184873e-05, + -0.000107500091550635, -5.1379722947632e-07}, + {-36.6150844777671, 3.24952006904945, 1.7222457840185, -0.0846362445435584, -0.0625549615377418, + 0.019178365782485, 0.000664877496455304, 0.000942971403881222, 0.000190754698755098, + -0.000372226659190439}}; + susHandlingParameters.sus10coeffAlpha = { + {14.4562393748324, 0.669162330324919, 2.13895255446541, -0.0161997097021299, + 0.00185995785065838, 0.0621351118528379, -0.000278999272493087, 0.000238469666491965, + -0.000279407497782961, 0.000726904943739837}, + {-4.45678285887022, 0.92869611919737, 0.186752102727282, -0.00706160758952316, + 0.00532680276723634, -0.00119102617674229, -0.000105283880098953, 3.90673052334419e-05, + -3.13338277344246e-05, 5.32977236959767e-06}, + {30.4255268053197, 3.00991076401191, -1.4855621363519, 0.033934286288413, -0.0553588742704929, + 0.0299275582316466, 0.000167915322354466, -0.00050925078118232, 0.000463662961330962, + -0.000232919143454163}, + {2.45076465343337, 1.30206564388838, 0.635121046212765, 0.00517109639797675, + 0.00360579544364496, 0.0198490668911362, -9.31556816982662e-05, 6.7313653707875e-05, + 6.4669137025142e-05, 0.000209727581169138}, + {-0.784841314851562, 1.10058314980836, 0.314063830836532, 0.000583003703415889, + 0.000312635453606579, -0.000183738114552387, 0.000214096205760617, -0.000286744686021244, + 0.000159157597180407, -0.00032235099420715}, + {7.19568036510586, 1.33307479701657, -0.465585141952456, -0.0031910726544199, + -0.00546273504371797, 0.0145494754402526, -7.9863949693769e-05, 4.83681329120104e-05, + 8.85844309936609e-05, -0.000143217870916994}, + {-12.8344546267449, 1.36023633150143, -0.728527724854506, 0.019982118403416, 0.0385056413989437, + -0.00468598272326268, -0.000303957957649245, -6.37783846968216e-05, 0.000514049116643205, + 0.000112015427600697}, + {-2.58279031298065, 1.42167821629586, 0.208769467511292, -0.00640190372145885, + -0.0056405289717473, 0.000509611313918708, 2.23310562107823e-05, 3.23685469522147e-05, + -7.55982776243849e-06, 2.78417756661088e-06}, + {-29.7178996143914, 2.636972251183, 1.97316329325243, -0.03983524158327, -0.0193152048730234, + -0.0600902798379509, 0.00031786916010672, 0.000162178988605602, 0.000224550786416246, + 0.000614337977361927}}; + susHandlingParameters.sus10coeffBeta = { + {12.4771349792459, 1.44317849705414, 0.975637226331561, 0.0430284146301043, 0.0220810531548995, + -0.0220926906772, 0.000310052324529521, 0.000658151808869523, -0.000288026365111098, + -0.000214619731807045}, + {-0.113203260140131, -0.272424061092191, 1.27704377191184, -0.00791746619331075, + 0.00278646694862191, -0.00398881099259934, -8.09569694307212e-05, 5.99617384829016e-05, + -5.4550919751855e-05, -8.6314530565085e-05}, + {-48.585664295448, -2.04899787231903, 4.48757129623549, -0.0226180460431321, 0.090326735447661, + -0.0722998813632622, -6.77623771415477e-05, 0.000562585419036509, -0.000956171370931993, + 0.000491554402311223}, + {-1.20986884955482, -0.215604107185474, 1.22123198786617, 0.000256508527822089, + -0.00625056735692847, 0.00262961582224303, 2.27433984698861e-05, 1.60471509861372e-05, + -4.85061736834262e-05, -1.8387092782907e-06}, + {-0.250205907903409, -0.315819331560782, 1.09018364376391, -0.000521787614293089, + -0.000500747760913489, 2.48184307342838e-05, 0.000313799238640988, 0.000136669146368744, + 0.000278914324565192, 0.000218512838469476}, + {-1.38512578184076, -0.240456589364121, 1.34170304231345, 0.00017499230372669, + 0.0070862275911073, -0.00460640844814105, 1.27594111036696e-05, -4.73855624902052e-06, + -5.41141037812903e-05, 8.50767021818388e-06}, + {58.9917559342216, -2.28705697628345, 5.35995190407842, 0.0214721399750612, -0.112195722921667, + 0.0890150265857542, -0.000100675657768708, 0.000493488022135339, -0.00137672908303878, + 0.000518683157694955}, + {3.18905073365834, -0.633376549706314, 1.17190259811174, 0.0188817945597344, + 0.00107470708915782, 0.00400880471375267, -0.000197312295539118, -2.46543035998379e-05, + -6.07871064300252e-05, 1.91822310311955e-05}, + {-21.6881499304099, -0.563186103920008, 3.70747028664292, 0.021112883967427, + -0.00650020689049325, -0.0778533644688476, -0.000131921888670268, -0.000402754836445439, + 0.000551249824375055, 0.00062236627391337}}; + susHandlingParameters.sus11coeffAlpha = { + {-5.23569698615548, -1.45500092391928, 2.7643243644756, -0.0762912296128707, + -0.0201645929971608, 0.0997226845779083, -0.000741669441569556, -0.000485368004931528, + 0.000166230212359982, 0.00103455037278067}, + {-7.7405077383712, 0.892040861541276, 0.39014957203484, -0.00952030929935314, + 0.0185577462685363, 0.000500600568760257, -0.000151227821554572, 0.000245334737283439, + 1.89380065823205e-05, 1.83481122973969e-07}, + {-27.462143709831, -1.68192474287299, 0.689411302961069, -0.0146021086710062, 0.227153492753605, + 0.0815806579791421, 2.92919049429149e-05, 0.00153760357651792, -0.00247865821192621, + -0.00166333309739387}, + {-6.74664748624368, 1.43279156053015, 0.0212787292914553, 0.00764792230365732, + 0.00796410301290615, 0.0014384998868733, -8.95239151813685e-05, 9.55245417090909e-05, + 0.000127251739461239, 3.26943341606363e-05}, + {-2.20391533717674, 1.32902400478083, 0.38633027011889, 0.00104660852197061, + 0.00105228824412283, -0.00242067551428214, -6.98346290136652e-05, -0.000369075232184835, + -1.59510520000704e-05, -0.000448565104826966}, + {-5.29476778147188, 1.4549556336236, 0.561334186252557, -0.00260896342687109, + -0.00855934179001141, -0.0182515354646452, -8.79385828606048e-05, 5.98357681659175e-05, + 0.000146570207542509, 0.000201596912834554}, + {-45.7906613832612, 3.77630104475902, -1.67494598155515, -0.0545433897761635, 0.047897938410221, + -0.0355687158405231, 0.000374738707508583, -0.000448453494537518, 0.000377784972619365, + -0.000276573228333836}, + {-9.11681182090372, 2.06933872940742, 0.26131496122122, -0.0259534033367855, + -0.00777266937872862, -0.00262135395843891, 0.000223790782655445, 6.40488537928934e-05, + 7.75581514100296e-05, -9.25934285039627e-06}, + {183.243883340634, -8.02281039502717, -10.0756951652703, 0.168750521462303, 0.314006821405967, + 0.200264755034566, -0.0011895153717447, -0.00253812476819896, -0.00291324393641628, + -0.00140062522117514}}; + susHandlingParameters.sus11coeffBeta = { + {34.4499366074013, -0.438583698052091, 4.72111001451028, -0.041810050989433, 0.0562461093661426, + 0.0856849892524893, -0.000477813051406167, -3.16404257494464e-05, 0.00102633196865105, + 0.000552974013759876}, + {7.6366298088699, 0.150314752958302, 1.31364679484924, 0.00557696667395871, 0.00163731860604376, + -0.00454759608980269, 5.83979683674572e-05, 4.45944881220665e-05, -4.27874746147066e-05, + -8.77418673597557e-05}, + {130.156215011893, 1.85759000444524, -10.986892391833, -0.00686275191260681, -0.188837138116058, + 0.346177462085361, -0.000183276946352264, -0.000702183496893294, 0.00293145272693857, + -0.00318194442670715}, + {-1.67854820161036, -0.358899332859806, 0.956690839640595, -4.93862910503803e-05, + -0.0136134783014874, -0.00848731301504507, 3.75950499927045e-05, 1.35374694383289e-06, + -0.000156596507890443, -0.000123254220377897}, + {3.67569209537767, -0.387260959713287, 1.31343215605952, -0.00206444615206506, + 0.00145334813110285, -0.00151259497696238, 0.000449492568365603, 6.95883968949488e-07, + 0.000368585523744765, -6.3420715525635e-05}, + {14.3296323024886, -0.182979476956897, 0.306817119309235, -0.00022212115978293, + 0.00463485302909649, 0.0277574953550035, 1.1422454625565e-05, 1.06053257479502e-05, + -2.05720000720608e-05, -0.000338584671430337}, + {-18.7534921817754, 1.14272710923224, 0.460498062012866, -0.00995826989278202, + 0.0658502318647112, 0.00616942819937029, -7.70857153768402e-05, -0.000641755741925561, + 0.00047849204592989, 0.000158509018296766}, + {1.26543621388607, -0.176674379740481, 1.38814920935488, 0.00545485262295305, + -0.00499775616702264, 0.0038057039142173, -6.59604252054511e-05, 6.40211116049053e-05, + -6.74778593434431e-05, -2.81973589469059e-05}, + {116.975421945286, -5.53022680362263, -5.61081660666997, 0.109754904982136, 0.167666815691513, + 0.163137400730063, -0.000609874123906977, -0.00205336098697513, -0.000889232196185857, + -0.00168429567131815}}; + + rwHandlingParameters.inertiaWheel = 0.000028198; rwHandlingParameters.maxTrq = 0.0032; //3.2 [mNm] diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 6e8fd1a2..494ddb68 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -51,6 +51,31 @@ public: float sus10orientationMatrix[3][3]; float sus11orientationMatrix[3][3]; + float sus0coeffAlpha[9][10]; // FM07 + float sus0coeffBeta[9][10]; + float sus1coeffAlpha[9][10]; // FM06 + float sus1coeffBeta[9][10]; + float sus2coeffAlpha[9][10]; // FM13 + float sus2coeffBeta[9][10]; + float sus3coeffAlpha[9][10]; // FM14 + float sus3coeffBeta[9][10]; + float sus4coeffAlpha[9][10]; // FM05 + float sus4coeffBeta[9][10]; + float sus5coeffAlpha[9][10]; // FM02 + float sus5coeffBeta[9][10]; + float sus6coeffAlpha[9][10]; // FM10 + float sus6coeffBeta[9][10]; + float sus7coeffAlpha[9][10]; // FM01 + float sus7coeffBeta[9][10]; + float sus8coeffAlpha[9][10]; // FM03 + float sus8coeffBeta[9][10]; + float sus9coeffAlpha[9][10]; // FM11 + float sus9coeffBeta[9][10]; + float sus10coeffAlpha[9][10]; // FM09 + float sus10coeffBeta[9][10]; + float sus11coeffAlpha[9][10]; // FM08 + float sus11coeffBeta[9][10]; + float filterAlpha; float sunThresh; } susHandlingParameters; -- 2.34.1 From 4b96997f6cc9e09999cd3cbfac4502d6948f6fa1 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 22 Sep 2022 14:47:53 +0200 Subject: [PATCH 022/101] added SUS transformation matrices to AcsParameters --- mission/controller/acs/AcsParameters.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index 92273e04..8559d868 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -35,6 +35,7 @@ AcsParameters::AcsParameters() { { 0, 1, 0}}; + susHandlingParameters.sus0orientationMatrix = {{0, 0, 1}, {1, 0, 0}, {0, 1, 0}}; susHandlingParameters.sus0coeffAlpha = { {10.4400948050067, 1.38202655603079, 0.975299591736672, 0.0172133914423707, -0.0163482459492803, 0.035730152619911, 0.00021725657060767, -0.000181685375645396, -0.000124096561459262, @@ -91,6 +92,7 @@ AcsParameters::AcsParameters() { {-32.3807957489507, 1.8271436443167, 2.51530814328123, -0.0532334586403461, -0.0355980127727253, -0.0213373892796204, 0.00045506092539885, 0.000545065581027688, 0.000141998709314758, 0.000101051304611037}}; + susHandlingParameters.sus1orientationMatrix = {{0, 0, -1}, {-1, 0, 0}, {0, 1, 0}}; susHandlingParameters.sus1coeffAlpha = { {-27.6783250420482, -0.964805032861791, -0.503974297997131, -0.0446471081874084, -0.048219538329297, 0.000958491361905381, -0.000290972187162876, -0.000657145721554176, @@ -147,6 +149,7 @@ AcsParameters::AcsParameters() { {-20.959201441285, -2.23605897639125, 5.73044624806043, 0.0354141964763815, 0.0887545371234514, -0.193862330062381, 0.000216532998121618, -0.00207707610520973, 0.000552928905346826, 0.00190182163597828}}; + susHandlingParameters.sus2orientationMatrix = {{-1, 0, 0}, {0, 0, -1}, {0, -1, 0}}; susHandlingParameters.sus2coeffAlpha = { {6.51602979328333, 0.690575501042577, 1.18185457002269, -0.0153161662266588, 0.00145972227341484, 0.0351496474730776, -0.000172645571366945, -6.04213053580018e-05, @@ -203,6 +206,7 @@ AcsParameters::AcsParameters() { {-59.5882618930651, 3.84530212586425, 3.50497032358686, -0.116100453177197, -0.0380997421813177, -0.0581898335691109, 0.00111464935006159, 0.000559313074537689, 0.000168067749764069, 0.000563224178849256}}; + susHandlingParameters.sus3orientationMatrix = {{1, 0, 0}, {0, 0, 1}, {0, -1, 0}}; susHandlingParameters.sus3coeffAlpha = { {-174.687021034355, -7.53454036765748, -9.33798316371397, -0.18212338430986, -0.242523652239734, -0.202086838965846, -0.00138648793335223, -0.00225430176012882, -0.00198887215340364, @@ -259,6 +263,7 @@ AcsParameters::AcsParameters() { {44.8818060495112, -7.94729992210875, 3.59286389225051, 0.217944601088562, 0.108087933176612, -0.116711715153385, -0.00194260120960441, -0.0015752762498594, -0.000331129410732722, 0.00125896996438418}}; + susHandlingParameters.sus4orientationMatrix = {{0, -1, 0}, {1, 0, 0}, {0, 0, 1}}; susHandlingParameters.sus4coeffAlpha = { {-12.4581187126738, 0.398038572289047, -0.438887880988151, -0.00965382887938283, -0.0309322349328842, -0.00359106522420111, -7.79546112299913e-06, -0.000432733997178497, @@ -315,6 +320,7 @@ AcsParameters::AcsParameters() { {-74.1601853968901, 2.55641628908672, 6.38533530714782, -0.0582345132980647, -0.0653804553172819, -0.138850555683872, 0.000489364157827405, 0.000469559629292745, 0.000698140692952438, 0.00123017528239406}}; + susHandlingParameters.sus5orientationMatrix = {{1, 0, 0}, {0, -1, 0}, {0, 0, -1}}; susHandlingParameters.sus5coeffAlpha = { {-12.1398741236355, 1.99425442858125, -1.9303044815802, 0.0418421279520049, -0.0309683799946315, -0.0562201123081437, 0.000522607299552916, -0.000375386573815007, -0.000183899715035788, @@ -371,6 +377,7 @@ AcsParameters::AcsParameters() { {-38.3689359928435, 3.8540516906071, 1.26391725545116, -0.108584643500539, -0.0542697403292778, 0.0285360568428252, 0.000845084580479371, 0.00114184315411245, -0.000169538153750085, -0.000336529204350355}}; + susHandlingParameters.sus6orientationMatrix = {{0, 0, 1}, {1, 0, 0}, {0, 1, 0}}; susHandlingParameters.sus6coeffAlpha = { {13.0465222152293, 0.0639132159808454, 2.98083557560227, -0.0773202212713293, 0.0949075412003712, 0.0503055998355815, -0.00104133434256204, 0.000633099036136146, @@ -427,6 +434,7 @@ AcsParameters::AcsParameters() { {1.95050549495182, -2.74909818412705, 3.80268788018641, 0.0629242254381785, 0.0581479035315726, -0.111361283351269, -0.00047845777495158, -0.00075354297736741, -0.000186887396585446, 0.00119710704771344}}; + susHandlingParameters.sus7orientationMatrix = {{0, 0, -1}, {-1, 0, 0}, {0, 1, 0}}; susHandlingParameters.sus7coeffAlpha = { {-92.1126183408754, -3.77261746189525, -4.50604668349213, -0.0909560776043523, -0.15646903318971, -0.0766293642415356, -0.00059452135473577, -0.00144790037129283, @@ -483,6 +491,7 @@ AcsParameters::AcsParameters() { {191.321181158032, -12.2449557187473, -7.21933741885107, 0.267954293388644, 0.331529493933124, 0.149867703984027, -0.00222279201444128, -0.00284724570619954, -0.00298774060233964, -0.000988903783752156}}; + susHandlingParameters.sus8orientationMatrix = {{-1, 0, 0}, {0, 0, -1}, {0, -1, 0}}; susHandlingParameters.sus8coeffAlpha = { {5.46354311880959, 1.15370126035432, 0.568432485840475, -0.00105094692478431, -0.000472899673842554, 0.015581320536192, 2.26460844314248e-05, -0.000254397947062058, @@ -539,6 +548,7 @@ AcsParameters::AcsParameters() { {64.9193383444005, -1.57724255547465, -3.82166532626293, 0.0104712238987591, 0.0898786950946473, 0.128910456296131, -8.27123227422217e-05, -0.000143979624107479, -0.00146684876653306, -0.00102226799570239}}; + susHandlingParameters.sus9orientationMatrix = {{1, 0, 0}, {0, 0, 1}, {0, -1, 0}}; susHandlingParameters.sus9coeffAlpha = { {65.8975109449121, 2.19115342242175, 6.11069527811832, -0.0219884864133703, 0.119985456538482, 0.142746712551924, -0.000465882328687976, 0.000606525132125852, 0.00141667074621881, @@ -595,6 +605,7 @@ AcsParameters::AcsParameters() { {-36.6150844777671, 3.24952006904945, 1.7222457840185, -0.0846362445435584, -0.0625549615377418, 0.019178365782485, 0.000664877496455304, 0.000942971403881222, 0.000190754698755098, -0.000372226659190439}}; + susHandlingParameters.sus10orientationMatrix = {{0, -1, 0}, {1, 0, 0}, {0, 0, 1}}; susHandlingParameters.sus10coeffAlpha = { {14.4562393748324, 0.669162330324919, 2.13895255446541, -0.0161997097021299, 0.00185995785065838, 0.0621351118528379, -0.000278999272493087, 0.000238469666491965, @@ -651,6 +662,7 @@ AcsParameters::AcsParameters() { {-21.6881499304099, -0.563186103920008, 3.70747028664292, 0.021112883967427, -0.00650020689049325, -0.0778533644688476, -0.000131921888670268, -0.000402754836445439, 0.000551249824375055, 0.00062236627391337}}; + susHandlingParameters.sus11orientationMatrix = {{1, 0, 0}, {0, -1, 0}, {0, 0, -1}}; susHandlingParameters.sus11coeffAlpha = { {-5.23569698615548, -1.45500092391928, 2.7643243644756, -0.0762912296128707, -0.0201645929971608, 0.0997226845779083, -0.000741669441569556, -0.000485368004931528, -- 2.34.1 From e70ee1bf9d61d5a7cffa64bdf24e3e0bbf3278a7 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Fri, 23 Sep 2022 09:56:32 +0200 Subject: [PATCH 023/101] initial commit of SusConverter --- mission/controller/acs/SusConverter.cpp | 382 ++++++++++++++++++++++++ mission/controller/acs/SusConverter.h | 59 ++++ 2 files changed, 441 insertions(+) create mode 100644 mission/controller/acs/SusConverter.cpp create mode 100644 mission/controller/acs/SusConverter.h diff --git a/mission/controller/acs/SusConverter.cpp b/mission/controller/acs/SusConverter.cpp new file mode 100644 index 00000000..0ef2fd28 --- /dev/null +++ b/mission/controller/acs/SusConverter.cpp @@ -0,0 +1,382 @@ +/* + * SusConverter.cpp + * + * Created on: 17.01.2022 + * Author: Timon Schwarz + */ + +#include //for atan2 +#include +#include + +void SunSensor::setSunSensorData(uint8_t Sensornumber) { + // Creates dummy sensordata, replace with SUS devicehandler / channel readout + ChannelValue[0] = 3913; + ChannelValue[1] = 3912; + ChannelValue[2] = 3799; + ChannelValue[3] = 3797; + ChannelValue[4] = 4056; +} + +void SunSensor::checkSunSensorData(uint8_t Sensornumber) { + uint16_t ChannelValueSum; + + // Check individual channel values + for (int k = 0; k < 4; k++) { // iteration above all photodiode quarters + + if (ChannelValue[k] <= ChannelValueCheckLow || + ChannelValue[k] > ChannelValueCheckHigh) { // Channel values out of range for 12 bit SUS + // channel measurement range? + ValidityNumber = false; // false --> Data not valid + printf( + "The value of channel %i from sun sensor %i is not inside the borders of valid data with " + "a value of %i \n", + k, Sensornumber, ChannelValue[k]); + } else if (ChannelValue[k] > + ChannelValue[4]) { // Channel values higher than zero current threshold GNDREF? + ValidityNumber = false; + printf( + "The value of channel %i from sun sensor %i is higher than the zero current threshold " + "GNDREF\n", + k, Sensornumber); + }; + }; + + // check sum of all channel values to check if sun sensor is illuminated by the sun (sum is + // smaller than a treshold --> sun sensor is not illuminated by the sun, but by the moon + // reflection or earth albedo) + ChannelValueSum = + 4 * ChannelValue[4] - (ChannelValue[0] + ChannelValue[1] + ChannelValue[2] + ChannelValue[3]); + if ((ChannelValueSum < ChannelValueSumHigh) && (ChannelValueSum > ChannelValueSumLow)) { + ValidityNumber = false; + printf("Sun sensor %i is not illuminated by the sun\n", Sensornumber); + }; +} + +void SunSensor::AngleCalculation() { + float xout, yout, s = 0.03; // s=[mm] + uint8_t d = 5, h = 1; // d=[mm] h=[mm] + int ch0, ch1, ch2, ch3; + // Substract measurement values from GNDREF zero current threshold + ch0 = ChannelValue[4] - ChannelValue[0]; + ch1 = ChannelValue[4] - ChannelValue[1]; + ch2 = ChannelValue[4] - ChannelValue[2]; + ch3 = ChannelValue[4] - ChannelValue[3]; + + // Calculation of x and y + xout = ((d - s) / 2) * (ch2 - ch3 - ch0 + ch1) / (ch0 + ch1 + ch2 + ch3); //[mm] + yout = ((d - s) / 2) * (ch2 + ch3 - ch0 - ch1) / (ch0 + ch1 + ch2 + ch3); //[mm] + + // Calculation of the angles + AlphaBetaRaw[0] = atan2(xout, h) * (180 / M_PI); //[°] + AlphaBetaRaw[1] = atan2(yout, h) * (180 / M_PI); //[°] +} + +void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { + switch (Sensornumber) { // search for the correct calibration coefficients for each SUS + + case 0: + for (uint8_t row = 0; row < 9; + row++) { // save the correct coefficients in the right SUS class + for (uint8_t column = 0; column < 10; column++) { + CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus0coeffAlpha[row][column]; + CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus0coeffBeta[row][column]; + } + } + break; + + case 1: + for (uint8_t row = 0; row < 9; row++) { + for (uint8_t column = 0; column < 10; column++) { + CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus1coeffAlpha[row][column]; + CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus1coeffBeta[row][column]; + } + } + break; + + case 2: + for (uint8_t row = 0; row < 9; row++) { + for (uint8_t column = 0; column < 10; column++) { + CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus2coeffAlpha[row][column]; + CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus2coeffBeta[row][column]; + } + } + break; + + case 3: + for (uint8_t row = 0; row < 9; row++) { + for (uint8_t column = 0; column < 10; column++) { + CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus3coeffAlpha[row][column]; + CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus3coeffBeta[row][column]; + } + } + break; + + case 4: + for (uint8_t row = 0; row < 9; row++) { + for (uint8_t column = 0; column < 10; column++) { + CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus4coeffAlpha[row][column]; + CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus4coeffBeta[row][column]; + } + } + break; + + case 5: + for (uint8_t row = 0; row < 9; row++) { + for (uint8_t column = 0; column < 10; column++) { + CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus5coeffAlpha[row][column]; + CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus5coeffBeta[row][column]; + } + } + break; + + case 6: + for (uint8_t row = 0; row < 9; row++) { + for (uint8_t column = 0; column < 10; column++) { + CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus6coeffAlpha[row][column]; + CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus6coeffBeta[row][column]; + } + } + break; + + case 7: + for (uint8_t row = 0; row < 9; row++) { + for (uint8_t column = 0; column < 10; column++) { + CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus7coeffAlpha[row][column]; + CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus7coeffBeta[row][column]; + } + } + break; + + case 8: + for (uint8_t row = 0; row < 9; row++) { + for (uint8_t column = 0; column < 10; column++) { + CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus8coeffAlpha[row][column]; + CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus8coeffBeta[row][column]; + } + } + break; + + case 9: + for (uint8_t row = 0; row < 9; row++) { + for (uint8_t column = 0; column < 10; column++) { + CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus9coeffAlpha[row][column]; + CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus9coeffBeta[row][column]; + } + } + break; + + case 10: + for (uint8_t row = 0; row < 9; row++) { + for (uint8_t column = 0; column < 10; column++) { + CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus10coeffAlpha[row][column]; + CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus10coeffBeta[row][column]; + } + } + break; + + case 11: + for (uint8_t row = 0; row < 9; row++) { + for (uint8_t column = 0; column < 10; column++) { + CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus11coeffAlpha[row][column]; + CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus11coeffBeta[row][column]; + } + } + break; + } +} + +void SunSensor::Calibration() { + float alpha_m, beta_m, alpha_calibrated, beta_calibrated, k, l; + uint8_t index; + + alpha_m = AlphaBetaRaw[0]; //[°] + beta_m = AlphaBetaRaw[1]; //[°] + + // while loop iterates above all calibration cells to use the different calibration functions in + // each cell + k = 0; + while (k < 3) { + k = k + 1; + l = 0; + while (l < 3) { + l = l + 1; + // if-condition to check in which cell the data point has to be + if ((alpha_m > ((CompleteCellWidth * ((k - 1) / 3)) - HalfCellWidth) && + alpha_m < ((CompleteCellWidth * (k / 3)) - HalfCellWidth)) && + (beta_m > ((CompleteCellWidth * ((l - 1) / 3)) - HalfCellWidth) && + beta_m < ((CompleteCellWidth * (l / 3)) - HalfCellWidth))) { + index = (3 * (k - 1) + l) - 1; // calculate the index of the datapoint for the right cell + // -> first cell has number 0 + alpha_calibrated = + CoeffAlpha[index][0] + CoeffAlpha[index][1] * alpha_m + CoeffAlpha[index][2] * beta_m + + CoeffAlpha[index][3] * alpha_m * alpha_m + CoeffAlpha[index][4] * alpha_m * beta_m + + CoeffAlpha[index][5] * beta_m * beta_m + + CoeffAlpha[index][6] * alpha_m * alpha_m * alpha_m + + CoeffAlpha[index][7] * alpha_m * alpha_m * beta_m + + CoeffAlpha[index][8] * alpha_m * beta_m * beta_m + + CoeffAlpha[index][9] * beta_m * beta_m * beta_m; + } + } + } + + // while loop iterates above all calibration cells to use the different calibration functions in + // each cell + k = 0; + while (k < 3) { + k = k + 1; + l = 0; + while (l < 3) { + l = l + 1; + // if condition to check in which cell the data point has to be + if ((alpha_m > ((CompleteCellWidth * ((k - 1) / 3)) - HalfCellWidth) && + alpha_m < ((CompleteCellWidth * (k / 3)) - HalfCellWidth)) && + (beta_m > ((CompleteCellWidth * ((l - 1) / 3)) - HalfCellWidth) && + beta_m < ((CompleteCellWidth * (l / 3)) - HalfCellWidth))) { + index = (3 * (k - 1) + l) - 1; // calculate the index of the datapoint for the right cell + // -> first cell has number 0 + beta_calibrated = CoeffBeta[index][0] + CoeffBeta[index][1] * alpha_m + + CoeffBeta[index][2] * beta_m + CoeffBeta[index][3] * alpha_m * alpha_m + + CoeffBeta[index][4] * alpha_m * beta_m + + CoeffBeta[index][5] * beta_m * beta_m + + CoeffBeta[index][6] * alpha_m * alpha_m * alpha_m + + CoeffBeta[index][7] * alpha_m * alpha_m * beta_m + + CoeffBeta[index][8] * alpha_m * beta_m * beta_m + + CoeffBeta[index][9] * beta_m * beta_m * beta_m; + } + } + } + + AlphaBetaCalibrated[0] = alpha_calibrated; //[°] + AlphaBetaCalibrated[1] = beta_calibrated; //[°] +} + +void SunSensor::CalculateSunVector() { + float alpha, beta; + alpha = AlphaBetaCalibrated[0]; //[°] + beta = AlphaBetaCalibrated[1]; //[°] + + // Calculate the normalized Sun Vector + SunVectorBodyFrame[0] = + (tan(alpha * (M_PI / 180)) / + (sqrt((powf(tan(alpha * (M_PI / 180)), 2)) + powf(tan((beta * (M_PI / 180))), 2) + (1)))); + SunVectorBodyFrame[1] = + (tan(beta * (M_PI / 180)) / + (sqrt(powf((tan(alpha * (M_PI / 180))), 2) + powf(tan((beta * (M_PI / 180))), 2) + (1)))); + SunVectorBodyFrame[2] = + (-1 / + (sqrt(powf((tan(alpha * (M_PI / 180))), 2) + powf((tan(beta * (M_PI / 180))), 2) + (1)))); +} + +float* SunSensor::getSunVectorBodyFrame() { + // return function for the sun vector in the body frame + float* SunVectorBodyFrameReturn = 0; + SunVectorBodyFrameReturn = new float[3]; + + SunVectorBodyFrameReturn[0] = SunVectorBodyFrame[0]; + SunVectorBodyFrameReturn[1] = SunVectorBodyFrame[1]; + SunVectorBodyFrameReturn[2] = SunVectorBodyFrame[2]; + + return SunVectorBodyFrameReturn; +} + +float* SunSensor::TransferSunVector(SunSensor SUS[12]) { + float* SunVectorEIVE = 0; + SunVectorEIVE = new float[3]; + + uint8_t counter = 0; + int8_t BasisMatrixUse[3][3]; + float SunVectorMatrixEIVE[3][12] = {0}, sum; + float SunVectorMatrixBodyFrame[3][12]; + + for (uint8_t Sensornumber = 0; Sensornumber < 12; + Sensornumber++) { // save the sun vector of each SUS in their body frame into an array for + // further processing + float* SunVectorBodyFrame = this[Sensornumber].getSunVectorBodyFrame(); + SunVectorMatrixBodyFrame[0][Sensornumber] = SunVectorBodyFrame[0]; + SunVectorMatrixBodyFrame[1][Sensornumber] = SunVectorBodyFrame[1]; + SunVectorMatrixBodyFrame[2][Sensornumber] = SunVectorBodyFrame[2]; + } + + for (uint8_t Sensornumber = 0; Sensornumber < 12; Sensornumber++) { + if (SUS[Sensornumber].getValidityNumber() == false) { + counter = counter + 1; + } // if the SUS data is not valid -> + + for (uint8_t c1 = 0; c1 < 3; c1++) { + for (uint8_t c2 = 0; c2 < 3; c2++) { + switch (Sensornumber) { // find right basis matrix for each SUS + + case 0: + BasisMatrixUse[c1][c2] = AcsParameters[c1][c2]; + break; + case 1: + BasisMatrixUse[c1][c2] = BasisMatrix1[c1][c2]; + break; + case 2: + BasisMatrixUse[c1][c2] = BasisMatrix2[c1][c2]; + break; + case 3: + BasisMatrixUse[c1][c2] = BasisMatrix3[c1][c2]; + break; + case 4: + BasisMatrixUse[c1][c2] = BasisMatrix4[c1][c2]; + break; + case 5: + BasisMatrixUse[c1][c2] = BasisMatrix5[c1][c2]; + break; + case 6: + BasisMatrixUse[c1][c2] = BasisMatrix6[c1][c2]; + break; + case 7: + BasisMatrixUse[c1][c2] = BasisMatrix7[c1][c2]; + break; + case 8: + BasisMatrixUse[c1][c2] = BasisMatrix8[c1][c2]; + break; + case 9: + BasisMatrixUse[c1][c2] = BasisMatrix9[c1][c2]; + break; + case 10: + BasisMatrixUse[c1][c2] = BasisMatrix10[c1][c2]; + break; + case 11: + BasisMatrixUse[c1][c2] = BasisMatrix11[c1][c2]; + break; + } + } + } + + // matrix multiplication for transition in EIVE coordinatesystem + for (uint8_t p = 0; p < 3; p++) { + for (uint8_t q = 0; q < 3; q++) { + // normal matrix multiplication + SunVectorMatrixEIVE[p][Sensornumber] += + (BasisMatrixUse[p][q] * SunVectorMatrixBodyFrame[q][Sensornumber]); + } + } + } + + // ToDo: remove invalid SUSs from being used for calculating the combined sun vector + + if (counter < 12) { // Calculate one sun vector out of all sun vectors from the different SUS + for (uint8_t i = 0; i < 3; i++) { + sum = 0; + for (uint8_t Sensornumber = 0; Sensornumber < 12; Sensornumber++) { + sum += SunVectorMatrixEIVE[i][Sensornumber]; + printf("%f\n", SunVectorMatrixEIVE[i][Sensornumber]); + } + SunVectorEIVE[i] = + sum / (12 - counter); // FLAG Ergebnis ist falsch, kann an einem Fehler im Programm + // liegen, vermutlich aber an den falschen ChannelValues da die + // transformierten Sonnenvektoren jedes SUS plausibel sind + } + } else { + // No sus is valid + throw std::invalid_argument("No sun sensor is valid"); // throw error + } + + return SunVectorEIVE; +} + + diff --git a/mission/controller/acs/SusConverter.h b/mission/controller/acs/SusConverter.h new file mode 100644 index 00000000..6f1b7420 --- /dev/null +++ b/mission/controller/acs/SusConverter.h @@ -0,0 +1,59 @@ +/* + * SusConverter.h + * + * Created on: Sep 22, 2022 + * Author: marius + */ + +#ifndef MISSION_CONTROLLER_ACS_SUSCONVERTER_H_ +#define MISSION_CONTROLLER_ACS_SUSCONVERTER_H_ + + +#include +#include + +class SunSensor { + public: + SunSensor() {} + + void setSunSensorData(uint8_t Sensornumber); + void checkSunSensorData(uint8_t Sensornumber); + void AngleCalculation(); + void setCalibrationCoefficients(uint8_t Sensornumber); + void Calibration(); + void CalculateSunVector(); + + bool getValidityNumber() { return ValidityNumber; } + float* getSunVectorBodyFrame(); + float* TransferSunVector(SunSensor SUS[12]); + + private: + uint16_t ChannelValue[5]; //[Bit] + float AlphaBetaRaw[2]; //[°] + float AlphaBetaCalibrated[2]; //[°] + float SunVectorBodyFrame[3]; //[-] + + bool ValidityNumber = true; + + uint16_t ChannelValueCheckHigh = + 4096; //=2^12[Bit]high borderline for the channel values of one sun sensor for validity Check + uint8_t ChannelValueCheckLow = + 0; //[Bit]low borderline for the channel values of one sun sensor for validity Check + uint16_t ChannelValueSumHigh = + 100; // 4096[Bit]high borderline for check if the sun sensor is illuminated by the sun or by + // the reflection of sunlight from the moon/earth + uint8_t ChannelValueSumLow = + 0; //[Bit]low borderline for check if the sun sensor is illuminated + // by the sun or by the reflection of sunlight from the moon/earth + uint8_t CompleteCellWidth = 140, + HalfCellWidth = 70; //[°] Width of the calibration cells --> necessary for checking in + // which cell a data point should be + + float CoeffAlpha[9][10]; + float CoeffBeta[9][10]; + + AcsParameters acsParameters; +}; + + +#endif /* MISSION_CONTROLLER_ACS_SUSCONVERTER_H_ */ -- 2.34.1 From 46ec376e4d40ed4ad9c7c67ce150185ba5112859 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Fri, 23 Sep 2022 14:27:05 +0200 Subject: [PATCH 024/101] amended SusConverter for use as OBSW --- mission/controller/acs/SusConverter.cpp | 208 +++++++++++++----------- mission/controller/acs/SusConverter.h | 26 +-- 2 files changed, 125 insertions(+), 109 deletions(-) diff --git a/mission/controller/acs/SusConverter.cpp b/mission/controller/acs/SusConverter.cpp index 0ef2fd28..d29f3706 100644 --- a/mission/controller/acs/SusConverter.cpp +++ b/mission/controller/acs/SusConverter.cpp @@ -8,14 +8,22 @@ #include //for atan2 #include #include +#include -void SunSensor::setSunSensorData(uint8_t Sensornumber) { +void SunSensor::setSunSensorData() { // Creates dummy sensordata, replace with SUS devicehandler / channel readout - ChannelValue[0] = 3913; - ChannelValue[1] = 3912; - ChannelValue[2] = 3799; - ChannelValue[3] = 3797; - ChannelValue[4] = 4056; + susChannelValues[0] = {3913, 3912, 3799, 4056}; + susChannelValues[1] = {3913, 3912, 3799, 4056}; + susChannelValues[2] = {3913, 3912, 3799, 4056}; + susChannelValues[3] = {3913, 3912, 3799, 4056}; + susChannelValues[4] = {3913, 3912, 3799, 4056}; + susChannelValues[5] = {3913, 3912, 3799, 4056}; + susChannelValues[6] = {3913, 3912, 3799, 4056}; + susChannelValues[7] = {3913, 3912, 3799, 4056}; + susChannelValues[8] = {3913, 3912, 3799, 4056}; + susChannelValues[9] = {3913, 3912, 3799, 4056}; + susChannelValues[10] = {3913, 3912, 3799, 4056}; + susChannelValues[11] = {3913, 3912, 3799, 4056}; } void SunSensor::checkSunSensorData(uint8_t Sensornumber) { @@ -24,21 +32,21 @@ void SunSensor::checkSunSensorData(uint8_t Sensornumber) { // Check individual channel values for (int k = 0; k < 4; k++) { // iteration above all photodiode quarters - if (ChannelValue[k] <= ChannelValueCheckLow || - ChannelValue[k] > ChannelValueCheckHigh) { // Channel values out of range for 12 bit SUS + if (susChannelValues[Sensornumber][k] <= ChannelValueCheckLow || + susChannelValues[Sensornumber][k] > ChannelValueCheckHigh) { // Channel values out of range for 12 bit SUS // channel measurement range? - ValidityNumber = false; // false --> Data not valid - printf( + ValidityNumber[Sensornumber] = false; // false --> Data not valid + /*printf( "The value of channel %i from sun sensor %i is not inside the borders of valid data with " "a value of %i \n", - k, Sensornumber, ChannelValue[k]); - } else if (ChannelValue[k] > - ChannelValue[4]) { // Channel values higher than zero current threshold GNDREF? - ValidityNumber = false; - printf( + k, Sensornumber, ChannelValue[k]);*/ + } else if (susChannelValues[Sensornumber][k] > + susChannelValues[Sensornumber][4]) { // Channel values higher than zero current threshold GNDREF? + ValidityNumber[Sensornumber] = false; + /*printf( "The value of channel %i from sun sensor %i is higher than the zero current threshold " "GNDREF\n", - k, Sensornumber); + k, Sensornumber);*/ }; }; @@ -46,30 +54,32 @@ void SunSensor::checkSunSensorData(uint8_t Sensornumber) { // smaller than a treshold --> sun sensor is not illuminated by the sun, but by the moon // reflection or earth albedo) ChannelValueSum = - 4 * ChannelValue[4] - (ChannelValue[0] + ChannelValue[1] + ChannelValue[2] + ChannelValue[3]); + 4 * susChannelValues[Sensornumber][4] - (susChannelValues[Sensornumber][0] + + susChannelValues[Sensornumber][1] + susChannelValues[Sensornumber][2] + + susChannelValues[Sensornumber][3]); if ((ChannelValueSum < ChannelValueSumHigh) && (ChannelValueSum > ChannelValueSumLow)) { - ValidityNumber = false; - printf("Sun sensor %i is not illuminated by the sun\n", Sensornumber); + ValidityNumber[Sensornumber] = false; + //printf("Sun sensor %i is not illuminated by the sun\n", Sensornumber); }; } -void SunSensor::AngleCalculation() { +void SunSensor::AngleCalculation(uint8_t Sensornumber) { float xout, yout, s = 0.03; // s=[mm] uint8_t d = 5, h = 1; // d=[mm] h=[mm] int ch0, ch1, ch2, ch3; // Substract measurement values from GNDREF zero current threshold - ch0 = ChannelValue[4] - ChannelValue[0]; - ch1 = ChannelValue[4] - ChannelValue[1]; - ch2 = ChannelValue[4] - ChannelValue[2]; - ch3 = ChannelValue[4] - ChannelValue[3]; + ch0 = susChannelValues[Sensornumber][4] - susChannelValues[Sensornumber][0]; + ch1 = susChannelValues[Sensornumber][4] - susChannelValues[Sensornumber][1]; + ch2 = susChannelValues[Sensornumber][4] - susChannelValues[Sensornumber][2]; + ch3 = susChannelValues[Sensornumber][4] - susChannelValues[Sensornumber][3]; // Calculation of x and y xout = ((d - s) / 2) * (ch2 - ch3 - ch0 + ch1) / (ch0 + ch1 + ch2 + ch3); //[mm] yout = ((d - s) / 2) * (ch2 + ch3 - ch0 - ch1) / (ch0 + ch1 + ch2 + ch3); //[mm] // Calculation of the angles - AlphaBetaRaw[0] = atan2(xout, h) * (180 / M_PI); //[°] - AlphaBetaRaw[1] = atan2(yout, h) * (180 / M_PI); //[°] + AlphaBetaRaw[Sensornumber][0] = atan2(xout, h) * (180 / M_PI); //[°] + AlphaBetaRaw[Sensornumber][1] = atan2(yout, h) * (180 / M_PI); //[°] } void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { @@ -79,8 +89,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { for (uint8_t row = 0; row < 9; row++) { // save the correct coefficients in the right SUS class for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus0coeffAlpha[row][column]; - CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus0coeffBeta[row][column]; + CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus0coeffAlpha[row][column]; + CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus0coeffBeta[row][column]; } } break; @@ -88,8 +98,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 1: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus1coeffAlpha[row][column]; - CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus1coeffBeta[row][column]; + CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus1coeffAlpha[row][column]; + CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus1coeffBeta[row][column]; } } break; @@ -97,8 +107,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 2: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus2coeffAlpha[row][column]; - CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus2coeffBeta[row][column]; + CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus2coeffAlpha[row][column]; + CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus2coeffBeta[row][column]; } } break; @@ -106,8 +116,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 3: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus3coeffAlpha[row][column]; - CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus3coeffBeta[row][column]; + CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus3coeffAlpha[row][column]; + CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus3coeffBeta[row][column]; } } break; @@ -115,8 +125,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 4: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus4coeffAlpha[row][column]; - CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus4coeffBeta[row][column]; + CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus4coeffAlpha[row][column]; + CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus4coeffBeta[row][column]; } } break; @@ -124,8 +134,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 5: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus5coeffAlpha[row][column]; - CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus5coeffBeta[row][column]; + CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus5coeffAlpha[row][column]; + CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus5coeffBeta[row][column]; } } break; @@ -133,8 +143,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 6: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus6coeffAlpha[row][column]; - CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus6coeffBeta[row][column]; + CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus6coeffAlpha[row][column]; + CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus6coeffBeta[row][column]; } } break; @@ -142,8 +152,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 7: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus7coeffAlpha[row][column]; - CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus7coeffBeta[row][column]; + CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus7coeffAlpha[row][column]; + CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus7coeffBeta[row][column]; } } break; @@ -151,8 +161,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 8: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus8coeffAlpha[row][column]; - CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus8coeffBeta[row][column]; + CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus8coeffAlpha[row][column]; + CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus8coeffBeta[row][column]; } } break; @@ -160,8 +170,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 9: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus9coeffAlpha[row][column]; - CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus9coeffBeta[row][column]; + CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus9coeffAlpha[row][column]; + CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus9coeffBeta[row][column]; } } break; @@ -169,8 +179,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 10: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus10coeffAlpha[row][column]; - CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus10coeffBeta[row][column]; + CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus10coeffAlpha[row][column]; + CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus10coeffBeta[row][column]; } } break; @@ -178,20 +188,20 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 11: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[row][column] = acsParameters.susHandlingParameters.sus11coeffAlpha[row][column]; - CoeffBeta[row][column] = acsParameters.susHandlingParameters.sus11coeffBeta[row][column]; + CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus11coeffAlpha[row][column]; + CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus11coeffBeta[row][column]; } } break; } } -void SunSensor::Calibration() { +void SunSensor::Calibration(uint8_t Sensornumber) { float alpha_m, beta_m, alpha_calibrated, beta_calibrated, k, l; uint8_t index; - alpha_m = AlphaBetaRaw[0]; //[°] - beta_m = AlphaBetaRaw[1]; //[°] + alpha_m = AlphaBetaRaw[Sensornumber][0]; //[°] + beta_m = AlphaBetaRaw[Sensornumber][1]; //[°] // while loop iterates above all calibration cells to use the different calibration functions in // each cell @@ -209,13 +219,13 @@ void SunSensor::Calibration() { index = (3 * (k - 1) + l) - 1; // calculate the index of the datapoint for the right cell // -> first cell has number 0 alpha_calibrated = - CoeffAlpha[index][0] + CoeffAlpha[index][1] * alpha_m + CoeffAlpha[index][2] * beta_m + - CoeffAlpha[index][3] * alpha_m * alpha_m + CoeffAlpha[index][4] * alpha_m * beta_m + - CoeffAlpha[index][5] * beta_m * beta_m + - CoeffAlpha[index][6] * alpha_m * alpha_m * alpha_m + - CoeffAlpha[index][7] * alpha_m * alpha_m * beta_m + - CoeffAlpha[index][8] * alpha_m * beta_m * beta_m + - CoeffAlpha[index][9] * beta_m * beta_m * beta_m; + CoeffAlpha[Sensornumber][index][0] + CoeffAlpha[Sensornumber][index][1] * alpha_m + CoeffAlpha[Sensornumber][index][2] * beta_m + + CoeffAlpha[Sensornumber][index][3] * alpha_m * alpha_m + CoeffAlpha[Sensornumber][index][4] * alpha_m * beta_m + + CoeffAlpha[Sensornumber][index][5] * beta_m * beta_m + + CoeffAlpha[Sensornumber][index][6] * alpha_m * alpha_m * alpha_m + + CoeffAlpha[Sensornumber][index][7] * alpha_m * alpha_m * beta_m + + CoeffAlpha[Sensornumber][index][8] * alpha_m * beta_m * beta_m + + CoeffAlpha[Sensornumber][index][9] * beta_m * beta_m * beta_m; } } } @@ -235,35 +245,35 @@ void SunSensor::Calibration() { beta_m < ((CompleteCellWidth * (l / 3)) - HalfCellWidth))) { index = (3 * (k - 1) + l) - 1; // calculate the index of the datapoint for the right cell // -> first cell has number 0 - beta_calibrated = CoeffBeta[index][0] + CoeffBeta[index][1] * alpha_m + - CoeffBeta[index][2] * beta_m + CoeffBeta[index][3] * alpha_m * alpha_m + - CoeffBeta[index][4] * alpha_m * beta_m + - CoeffBeta[index][5] * beta_m * beta_m + - CoeffBeta[index][6] * alpha_m * alpha_m * alpha_m + - CoeffBeta[index][7] * alpha_m * alpha_m * beta_m + - CoeffBeta[index][8] * alpha_m * beta_m * beta_m + - CoeffBeta[index][9] * beta_m * beta_m * beta_m; + beta_calibrated = CoeffBeta[Sensornumber][index][0] + CoeffBeta[Sensornumber][index][1] * alpha_m + + CoeffBeta[Sensornumber][index][2] * beta_m + CoeffBeta[Sensornumber][index][3] * alpha_m * alpha_m + + CoeffBeta[Sensornumber][index][4] * alpha_m * beta_m + + CoeffBeta[Sensornumber][index][5] * beta_m * beta_m + + CoeffBeta[Sensornumber][index][6] * alpha_m * alpha_m * alpha_m + + CoeffBeta[Sensornumber][index][7] * alpha_m * alpha_m * beta_m + + CoeffBeta[Sensornumber][index][8] * alpha_m * beta_m * beta_m + + CoeffBeta[Sensornumber][index][9] * beta_m * beta_m * beta_m; } } } - AlphaBetaCalibrated[0] = alpha_calibrated; //[°] - AlphaBetaCalibrated[1] = beta_calibrated; //[°] + AlphaBetaCalibrated[Sensornumber][0] = alpha_calibrated; //[°] + AlphaBetaCalibrated[Sensornumber][1] = beta_calibrated; //[°] } -void SunSensor::CalculateSunVector() { +void SunSensor::CalculateSunVector(uint8_t Sensornumber) { float alpha, beta; - alpha = AlphaBetaCalibrated[0]; //[°] - beta = AlphaBetaCalibrated[1]; //[°] + alpha = AlphaBetaCalibrated[Sensornumber][0]; //[°] + beta = AlphaBetaCalibrated[Sensornumber][1]; //[°] // Calculate the normalized Sun Vector - SunVectorBodyFrame[0] = + SunVectorBodyFrame[Sensornumber][0] = (tan(alpha * (M_PI / 180)) / (sqrt((powf(tan(alpha * (M_PI / 180)), 2)) + powf(tan((beta * (M_PI / 180))), 2) + (1)))); - SunVectorBodyFrame[1] = + SunVectorBodyFrame[Sensornumber][1] = (tan(beta * (M_PI / 180)) / (sqrt(powf((tan(alpha * (M_PI / 180))), 2) + powf(tan((beta * (M_PI / 180))), 2) + (1)))); - SunVectorBodyFrame[2] = + SunVectorBodyFrame[Sensornumber][2] = (-1 / (sqrt(powf((tan(alpha * (M_PI / 180))), 2) + powf((tan(beta * (M_PI / 180))), 2) + (1)))); } @@ -280,7 +290,11 @@ float* SunSensor::getSunVectorBodyFrame() { return SunVectorBodyFrameReturn; } -float* SunSensor::TransferSunVector(SunSensor SUS[12]) { +bool SunSensor::getValidityNumber(uint8_t Sensornumber) { + return ValidityNumber[Sensornumber]; +} + +float* SunSensor::TransferSunVector() { float* SunVectorEIVE = 0; SunVectorEIVE = new float[3]; @@ -292,14 +306,14 @@ float* SunSensor::TransferSunVector(SunSensor SUS[12]) { for (uint8_t Sensornumber = 0; Sensornumber < 12; Sensornumber++) { // save the sun vector of each SUS in their body frame into an array for // further processing - float* SunVectorBodyFrame = this[Sensornumber].getSunVectorBodyFrame(); + float* SunVectorBodyFrame = SunVectorBodyFrame[Sensornumber]; SunVectorMatrixBodyFrame[0][Sensornumber] = SunVectorBodyFrame[0]; SunVectorMatrixBodyFrame[1][Sensornumber] = SunVectorBodyFrame[1]; SunVectorMatrixBodyFrame[2][Sensornumber] = SunVectorBodyFrame[2]; } for (uint8_t Sensornumber = 0; Sensornumber < 12; Sensornumber++) { - if (SUS[Sensornumber].getValidityNumber() == false) { + if (getValidityNumber(Sensornumber) == false) { counter = counter + 1; } // if the SUS data is not valid -> @@ -308,40 +322,40 @@ float* SunSensor::TransferSunVector(SunSensor SUS[12]) { switch (Sensornumber) { // find right basis matrix for each SUS case 0: - BasisMatrixUse[c1][c2] = AcsParameters[c1][c2]; + BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus0orientationMatrix[c1][c2]; break; case 1: - BasisMatrixUse[c1][c2] = BasisMatrix1[c1][c2]; + BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus1orientationMatrix[c1][c2]; break; case 2: - BasisMatrixUse[c1][c2] = BasisMatrix2[c1][c2]; + BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus2orientationMatrix[c1][c2]; break; case 3: - BasisMatrixUse[c1][c2] = BasisMatrix3[c1][c2]; + BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus3orientationMatrix[c1][c2]; break; case 4: - BasisMatrixUse[c1][c2] = BasisMatrix4[c1][c2]; + BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus4orientationMatrix[c1][c2]; break; case 5: - BasisMatrixUse[c1][c2] = BasisMatrix5[c1][c2]; + BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus5orientationMatrix[c1][c2]; break; case 6: - BasisMatrixUse[c1][c2] = BasisMatrix6[c1][c2]; + BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus6orientationMatrix[c1][c2]; break; case 7: - BasisMatrixUse[c1][c2] = BasisMatrix7[c1][c2]; + BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus7orientationMatrix[c1][c2]; break; case 8: - BasisMatrixUse[c1][c2] = BasisMatrix8[c1][c2]; + BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus8orientationMatrix[c1][c2]; break; case 9: - BasisMatrixUse[c1][c2] = BasisMatrix9[c1][c2]; + BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus9orientationMatrix[c1][c2]; break; case 10: - BasisMatrixUse[c1][c2] = BasisMatrix10[c1][c2]; + BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus10orientationMatrix[c1][c2]; break; case 11: - BasisMatrixUse[c1][c2] = BasisMatrix11[c1][c2]; + BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus11orientationMatrix[c1][c2]; break; } } @@ -357,20 +371,22 @@ float* SunSensor::TransferSunVector(SunSensor SUS[12]) { } } - // ToDo: remove invalid SUSs from being used for calculating the combined sun vector - if (counter < 12) { // Calculate one sun vector out of all sun vectors from the different SUS for (uint8_t i = 0; i < 3; i++) { sum = 0; for (uint8_t Sensornumber = 0; Sensornumber < 12; Sensornumber++) { - sum += SunVectorMatrixEIVE[i][Sensornumber]; - printf("%f\n", SunVectorMatrixEIVE[i][Sensornumber]); + if (getValidityNumber(Sensornumber)){ + sum += SunVectorMatrixEIVE[i][Sensornumber]; + //printf("%f\n", SunVectorMatrixEIVE[i][Sensornumber]); + } } + // ToDo: decide on length on sun vector SunVectorEIVE[i] = - sum / (12 - counter); // FLAG Ergebnis ist falsch, kann an einem Fehler im Programm + sum/* / (12 - counter)*/; // FLAG Ergebnis ist falsch, kann an einem Fehler im Programm // liegen, vermutlich aber an den falschen ChannelValues da die // transformierten Sonnenvektoren jedes SUS plausibel sind } + VectorOperations::normalize(SunVectorEIVE, SunVectorEIVE, 3); } else { // No sus is valid throw std::invalid_argument("No sun sensor is valid"); // throw error diff --git a/mission/controller/acs/SusConverter.h b/mission/controller/acs/SusConverter.h index 6f1b7420..4012bb5a 100644 --- a/mission/controller/acs/SusConverter.h +++ b/mission/controller/acs/SusConverter.h @@ -16,24 +16,24 @@ class SunSensor { public: SunSensor() {} - void setSunSensorData(uint8_t Sensornumber); + void setSunSensorData(); void checkSunSensorData(uint8_t Sensornumber); - void AngleCalculation(); + void AngleCalculation(uint8_t Sensornumber); void setCalibrationCoefficients(uint8_t Sensornumber); - void Calibration(); - void CalculateSunVector(); + void Calibration(uint8_t Sensornumber); + void CalculateSunVector(uint8_t Sensornumber); - bool getValidityNumber() { return ValidityNumber; } + bool getValidityNumber(uint8_t Sensornumber); float* getSunVectorBodyFrame(); - float* TransferSunVector(SunSensor SUS[12]); + float* TransferSunVector(); private: - uint16_t ChannelValue[5]; //[Bit] - float AlphaBetaRaw[2]; //[°] - float AlphaBetaCalibrated[2]; //[°] - float SunVectorBodyFrame[3]; //[-] + uint16_t susChannelValues[12][4]; //[Bit] + float AlphaBetaRaw[12][2]; //[°] + float AlphaBetaCalibrated[12][2]; //[°] + float SunVectorBodyFrame[12][3]; //[-] - bool ValidityNumber = true; + bool ValidityNumber[12] = true; uint16_t ChannelValueCheckHigh = 4096; //=2^12[Bit]high borderline for the channel values of one sun sensor for validity Check @@ -49,8 +49,8 @@ class SunSensor { HalfCellWidth = 70; //[°] Width of the calibration cells --> necessary for checking in // which cell a data point should be - float CoeffAlpha[9][10]; - float CoeffBeta[9][10]; + float CoeffAlpha[12][9][10]; + float CoeffBeta[12][9][10]; AcsParameters acsParameters; }; -- 2.34.1 From cd11e081932e1529148af327e9d1fbb47f5701ad Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Fri, 23 Sep 2022 14:37:48 +0200 Subject: [PATCH 025/101] removed redundant loop --- mission/controller/acs/SusConverter.cpp | 43 +++++++------------------ 1 file changed, 11 insertions(+), 32 deletions(-) diff --git a/mission/controller/acs/SusConverter.cpp b/mission/controller/acs/SusConverter.cpp index d29f3706..151648ed 100644 --- a/mission/controller/acs/SusConverter.cpp +++ b/mission/controller/acs/SusConverter.cpp @@ -218,47 +218,26 @@ void SunSensor::Calibration(uint8_t Sensornumber) { beta_m < ((CompleteCellWidth * (l / 3)) - HalfCellWidth))) { index = (3 * (k - 1) + l) - 1; // calculate the index of the datapoint for the right cell // -> first cell has number 0 - alpha_calibrated = + AlphaBetaCalibrated[Sensornumber][0] = CoeffAlpha[Sensornumber][index][0] + CoeffAlpha[Sensornumber][index][1] * alpha_m + CoeffAlpha[Sensornumber][index][2] * beta_m + CoeffAlpha[Sensornumber][index][3] * alpha_m * alpha_m + CoeffAlpha[Sensornumber][index][4] * alpha_m * beta_m + CoeffAlpha[Sensornumber][index][5] * beta_m * beta_m + CoeffAlpha[Sensornumber][index][6] * alpha_m * alpha_m * alpha_m + CoeffAlpha[Sensornumber][index][7] * alpha_m * alpha_m * beta_m + CoeffAlpha[Sensornumber][index][8] * alpha_m * beta_m * beta_m + - CoeffAlpha[Sensornumber][index][9] * beta_m * beta_m * beta_m; + CoeffAlpha[Sensornumber][index][9] * beta_m * beta_m * beta_m; //[°] + AlphaBetaCalibrated[Sensornumber][1] = + CoeffBeta[Sensornumber][index][0] + CoeffBeta[Sensornumber][index][1] * alpha_m + + CoeffBeta[Sensornumber][index][2] * beta_m + CoeffBeta[Sensornumber][index][3] * alpha_m * alpha_m + + CoeffBeta[Sensornumber][index][4] * alpha_m * beta_m + + CoeffBeta[Sensornumber][index][5] * beta_m * beta_m + + CoeffBeta[Sensornumber][index][6] * alpha_m * alpha_m * alpha_m + + CoeffBeta[Sensornumber][index][7] * alpha_m * alpha_m * beta_m + + CoeffBeta[Sensornumber][index][8] * alpha_m * beta_m * beta_m + + CoeffBeta[Sensornumber][index][9] * beta_m * beta_m * beta_m; //[°] } } } - - // while loop iterates above all calibration cells to use the different calibration functions in - // each cell - k = 0; - while (k < 3) { - k = k + 1; - l = 0; - while (l < 3) { - l = l + 1; - // if condition to check in which cell the data point has to be - if ((alpha_m > ((CompleteCellWidth * ((k - 1) / 3)) - HalfCellWidth) && - alpha_m < ((CompleteCellWidth * (k / 3)) - HalfCellWidth)) && - (beta_m > ((CompleteCellWidth * ((l - 1) / 3)) - HalfCellWidth) && - beta_m < ((CompleteCellWidth * (l / 3)) - HalfCellWidth))) { - index = (3 * (k - 1) + l) - 1; // calculate the index of the datapoint for the right cell - // -> first cell has number 0 - beta_calibrated = CoeffBeta[Sensornumber][index][0] + CoeffBeta[Sensornumber][index][1] * alpha_m + - CoeffBeta[Sensornumber][index][2] * beta_m + CoeffBeta[Sensornumber][index][3] * alpha_m * alpha_m + - CoeffBeta[Sensornumber][index][4] * alpha_m * beta_m + - CoeffBeta[Sensornumber][index][5] * beta_m * beta_m + - CoeffBeta[Sensornumber][index][6] * alpha_m * alpha_m * alpha_m + - CoeffBeta[Sensornumber][index][7] * alpha_m * alpha_m * beta_m + - CoeffBeta[Sensornumber][index][8] * alpha_m * beta_m * beta_m + - CoeffBeta[Sensornumber][index][9] * beta_m * beta_m * beta_m; - } - } - } - - AlphaBetaCalibrated[Sensornumber][0] = alpha_calibrated; //[°] - AlphaBetaCalibrated[Sensornumber][1] = beta_calibrated; //[°] } void SunSensor::CalculateSunVector(uint8_t Sensornumber) { -- 2.34.1 From e140ae4063a784a04eb13e3c722a4e6bf108ca4d Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 26 Sep 2022 10:13:00 +0200 Subject: [PATCH 026/101] fixed typo in filename --- mission/controller/acs/{Navitation.cpp => Navigation.cpp} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename mission/controller/acs/{Navitation.cpp => Navigation.cpp} (100%) diff --git a/mission/controller/acs/Navitation.cpp b/mission/controller/acs/Navigation.cpp similarity index 100% rename from mission/controller/acs/Navitation.cpp rename to mission/controller/acs/Navigation.cpp -- 2.34.1 From 2ede1ed27c694fc30d63bc5937ec84c04d79b299 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 26 Sep 2022 10:15:03 +0200 Subject: [PATCH 027/101] added CMake files for new directories. amended existing controller Cmake --- mission/controller/CMakeLists.txt | 2 ++ mission/controller/acs/CMakeLists.txt | 14 ++++++++++++++ mission/controller/acs/control/CMakeLists.txt | 5 +++++ 3 files changed, 21 insertions(+) create mode 100644 mission/controller/acs/CMakeLists.txt create mode 100644 mission/controller/acs/control/CMakeLists.txt diff --git a/mission/controller/CMakeLists.txt b/mission/controller/CMakeLists.txt index 84ff7f9e..463e6a5d 100644 --- a/mission/controller/CMakeLists.txt +++ b/mission/controller/CMakeLists.txt @@ -2,3 +2,5 @@ if(TGT_BSP MATCHES "arm/q7s" OR TGT_BSP MATCHES "") target_sources(${LIB_EIVE_MISSION} PRIVATE ThermalController.cpp AcsController.cpp) endif() + +add_subdirectory(acs) \ No newline at end of file diff --git a/mission/controller/acs/CMakeLists.txt b/mission/controller/acs/CMakeLists.txt new file mode 100644 index 00000000..c949a067 --- /dev/null +++ b/mission/controller/acs/CMakeLists.txt @@ -0,0 +1,14 @@ +target_sources( + ${LIB_EIVE_MISSION} + PRIVATE AcsParameters.cpp + ActuatorCmd.cpp + Guidance.cpp + Igrf13Model.cpp + MultiplicativeKalmanFilter.cpp + Navigation.cpp + OutputValues.cpp + SensorProcessing.cpp + SensorValues.cpp + SusConverter.cpp) + +add_subdirectory(control) diff --git a/mission/controller/acs/control/CMakeLists.txt b/mission/controller/acs/control/CMakeLists.txt new file mode 100644 index 00000000..dc540435 --- /dev/null +++ b/mission/controller/acs/control/CMakeLists.txt @@ -0,0 +1,5 @@ +target_sources( + ${LIB_EIVE_MISSION} + PRIVATE Detumble.cpp + PtgCtrl.cpp + SafeCtrl.cpp) \ No newline at end of file -- 2.34.1 From 96bbde7bbc280d7d918d245167125013599945e9 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 26 Sep 2022 10:39:57 +0200 Subject: [PATCH 028/101] removed HasReturnValuesIF --- mission/controller/acs/MultiplicativeKalmanFilter.cpp | 5 ++--- mission/controller/acs/MultiplicativeKalmanFilter.h | 2 +- mission/controller/acs/control/PtgCtrl.h | 5 ++--- mission/controller/acs/control/SafeCtrl.h | 2 +- 4 files changed, 6 insertions(+), 8 deletions(-) diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.cpp b/mission/controller/acs/MultiplicativeKalmanFilter.cpp index 5a546409..b2c8a963 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.cpp +++ b/mission/controller/acs/MultiplicativeKalmanFilter.cpp @@ -10,7 +10,6 @@ #include #include #include -#include #include "MultiplicativeKalmanFilter.h" #include #include @@ -300,7 +299,7 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst( else{ sensorsAvail = 8; //no measurements validMekf = false; - return RETURN_FAILED; + return returnvalue::FAILED; } // If we are here, MEKF will perform @@ -1201,5 +1200,5 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst( // Check for new data in measurement -> SensorProcessing ? - return RETURN_OK; + return returnvalue::OK; } diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.h b/mission/controller/acs/MultiplicativeKalmanFilter.h index d4370ad3..f972ab5a 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.h +++ b/mission/controller/acs/MultiplicativeKalmanFilter.h @@ -21,7 +21,7 @@ #include "AcsParameters.h" -class MultiplicativeKalmanFilter : public HasReturnvaluesIF { +class MultiplicativeKalmanFilter{ public: /* @brief: Constructor * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters diff --git a/mission/controller/acs/control/PtgCtrl.h b/mission/controller/acs/control/PtgCtrl.h index 5bd7f0da..fe5d0e96 100644 --- a/mission/controller/acs/control/PtgCtrl.h +++ b/mission/controller/acs/control/PtgCtrl.h @@ -19,11 +19,10 @@ #include #include #include -#include "acs/config/classIds.h" -#include +#include #include -class PtgCtrl : public HasReturnvaluesIF { +class PtgCtrl{ public: /* @brief: Constructor diff --git a/mission/controller/acs/control/SafeCtrl.h b/mission/controller/acs/control/SafeCtrl.h index b0ce6a90..36807bcc 100644 --- a/mission/controller/acs/control/SafeCtrl.h +++ b/mission/controller/acs/control/SafeCtrl.h @@ -17,7 +17,7 @@ #include #include -class SafeCtrl : public HasReturnvaluesIF { +class SafeCtrl{ public: -- 2.34.1 From e7b6ca42bf98a80cd0336628aa5df89cc54f8abb Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 26 Sep 2022 13:23:20 +0200 Subject: [PATCH 029/101] cleaned up includes --- mission/controller/acs/AcsParameters.cpp | 2 +- mission/controller/acs/Guidance.h | 2 +- mission/controller/acs/Igrf13Model.h | 4 ++-- mission/controller/acs/SensorProcessing.h | 2 +- mission/controller/acs/SensorValues.cpp | 2 +- mission/controller/acs/SensorValues.h | 2 +- mission/controller/acs/control/Detumble.h | 2 +- 7 files changed, 8 insertions(+), 8 deletions(-) diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index 8559d868..42408868 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -2,7 +2,7 @@ #include "AcsParameters.h" #include -#include +#include AcsParameters::AcsParameters() { diff --git a/mission/controller/acs/Guidance.h b/mission/controller/acs/Guidance.h index 76cfce77..736d8b9b 100644 --- a/mission/controller/acs/Guidance.h +++ b/mission/controller/acs/Guidance.h @@ -12,7 +12,7 @@ #include #include #include -#include +#include class Guidance { diff --git a/mission/controller/acs/Igrf13Model.h b/mission/controller/acs/Igrf13Model.h index b6f14e0f..3ea2cb40 100644 --- a/mission/controller/acs/Igrf13Model.h +++ b/mission/controller/acs/Igrf13Model.h @@ -17,10 +17,10 @@ #define IGRF13MODEL_H_ #include -//#include +#include #include #include -#include +#include // Output should be transformed to [T] instead of [nT] diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h index 43c93722..23abcc40 100644 --- a/mission/controller/acs/SensorProcessing.h +++ b/mission/controller/acs/SensorProcessing.h @@ -6,7 +6,7 @@ #define SENSORPROCESSING_H_ #include //uint8_t -#include /*purpose, timeval ?*/ +#include /*purpose, timeval ?*/ #include #include #include diff --git a/mission/controller/acs/SensorValues.cpp b/mission/controller/acs/SensorValues.cpp index 25f2d61f..414c93ef 100644 --- a/mission/controller/acs/SensorValues.cpp +++ b/mission/controller/acs/SensorValues.cpp @@ -4,7 +4,7 @@ * Created on: 30 Mar 2022 * Author: rooob */ -#include +#include #include #include diff --git a/mission/controller/acs/SensorValues.h b/mission/controller/acs/SensorValues.h index 566eec81..001b141b 100644 --- a/mission/controller/acs/SensorValues.h +++ b/mission/controller/acs/SensorValues.h @@ -95,5 +95,5 @@ public: }; } /* namespace ACS */ -#endif ENSORVALUES_H_ +#endif /*ENSORVALUES_H_*/ diff --git a/mission/controller/acs/control/Detumble.h b/mission/controller/acs/control/Detumble.h index 47efd49d..618be6c6 100644 --- a/mission/controller/acs/control/Detumble.h +++ b/mission/controller/acs/control/Detumble.h @@ -15,7 +15,7 @@ #include #include #include -#include +#include class Detumble{ -- 2.34.1 From dca433532998f4f54e4127ce5b6f31fe835b9ac6 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 27 Sep 2022 10:49:46 +0200 Subject: [PATCH 030/101] fixed array assignment after intialization --- mission/controller/acs/AcsParameters.cpp | 814 +------------------- mission/controller/acs/AcsParameters.h | 929 ++++++++++++++++++++--- 2 files changed, 830 insertions(+), 913 deletions(-) diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index 42408868..c22e8ede 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -4,819 +4,9 @@ #include #include -AcsParameters::AcsParameters() { +AcsParameters::AcsParameters() {} - onBoardParams.sampleTime = 0.1; - - inertiaEIVE.inertiaMatrix = { - { 1.0, 0.0, 0.0}, - { 0.0, 1.0, 0.0}, - { 0.0, 0.5, 1.0}}; - - mgmHandlingParameters.mgm0orientationMatrix = { - { 0, 0,-1}, - { 0, 1, 0}, - { 1, 0, 0}}; - mgmHandlingParameters.mgm1orientationMatrix = { - { 0, 0, 1}, - { 0,-1, 0}, - { 1, 0, 0}}; - mgmHandlingParameters.mgm2orientationMatrix = { - { 0, 0,-1}, - { 0, 1, 0}, - { 1 ,0, 0}}; - mgmHandlingParameters.mgm3orientationMatrix = { - { 0, 0, 1}, - { 0,-1, 0}, - { 1, 0, 0}}; - mgmHandlingParameters.mgm4orientationMatrix = { - { 0, 0,-1}, - {-1, 0, 0}, - { 0, 1, 0}}; - - - susHandlingParameters.sus0orientationMatrix = {{0, 0, 1}, {1, 0, 0}, {0, 1, 0}}; - susHandlingParameters.sus0coeffAlpha = { - {10.4400948050067, 1.38202655603079, 0.975299591736672, 0.0172133914423707, -0.0163482459492803, - 0.035730152619911, 0.00021725657060767, -0.000181685375645396, -0.000124096561459262, - 0.00040790566176981}, - {6.38281281805793, 1.81388255990089, 0.28679524291736, 0.0218036823758417, 0.010516766426651, - 0.000446101708841615, 0.00020187044149361, 0.000114957457831415, 1.63114413539632e-05, - -2.0187452317724e-05}, - {-29.3049094555, -0.506844002611835, 1.64911970541112, -0.0336282997119334, 0.053185806861685, - -0.028164943139695, -0.00021098074590512, 0.000643681643489995, -0.000249094601806692, - 0.000231466668650876}, - {-4.76233790255328, 1.1780710601961, -0.194257188545164, 0.00471817228628384, - -0.00183773644319332, -0.00570261621182479, -7.99203367291902e-05, 7.75752247926601e-05, - -9.78534772816957e-06, -4.72083745991256e-05}, - {0.692159025649028, 1.11895461388667, 0.341706834956496, 0.000237989648019541, - -0.000188322779563912, 0.000227310789253953, 0.000133001646828401, -0.000305810826248463, - 0.00010150571088124, -0.000367705461590854}, - {3.38094203317731, 1.24778838596815, 0.067807236112956, -0.00379395536123526, - -0.00339180589343601, -0.00188754615986649, -7.52406312245606e-05, 4.58398750278147e-05, - 6.97244631313601e-05, 2.50519145070895e-05}, - {-7.10546287716029, 0.459472977452686, -1.12251049944014, 0.0175406972371191, - -0.0310525406867782, -0.0531315970690727, -0.000121107664597462, 0.000544665437051928, - -1.78466217018177e-05, -0.00058976234038192}, - {1.60633684055984, 1.1975095485662, 0.180159204664965, -0.00259157601062089, - -0.0038106317634397, 0.000956686555225968, 4.28416721502134e-06, 5.84532336259517e-06, - -2.73407888222758e-05, 5.45131881032866e-06}, - {43.3732235586222, 0.528096786861784, -3.41255850703983, -0.0161629934278675, - 0.0790998053536612, 0.0743822668655928, 0.000237176965460634, -0.000426691336904078, - -0.000889196131314391, -0.000509766491897672}}; - susHandlingParameters.sus0coeffBeta = { - {1.03872648284911, -0.213507239271552, 1.43193059498181, -0.000972717820830235, - -0.00661046096415371, 0.00974284211491888, 2.96098456891215e-05, -8.2933115634257e-05, - -5.52178824394723e-06, 5.73935295303589e-05}, - {3.42242235823356, 0.0848392511283237, 1.24574390342586, 0.00356248195980133, - 0.00100415659893053, -0.00460120247716139, 3.84891005422427e-05, 2.70236417852327e-05, - -7.58501977656551e-05, -8.79809730730992e-05}, - {14.0092526123741, 1.03126714946215, 1.0611008563785, 0.04076462444523, 0.0114106419194518, - 0.00746959159048058, 0.000388033225774727, -0.000124645014888926, -0.000296639947532341, - -0.00020861690864945}, - {1.3562422681189, -0.241585615891602, 1.49170424068611, 0.000179184170448335, - -0.00712399257616284, 0.0121433526723498, 3.29770580642447e-05, 8.78960210966787e-06, - -6.00508568552101e-05, 0.000101583822589461}, - {-0.718855428908583, -0.344067476078684, 1.12397093701762, 0.000236505431484729, - -0.000406441415248947, 0.00032834991502413, 0.000359422093285086, 8.18895560425272e-05, - 0.000316835483508523, 0.000151442890664899}, - {-0.268764016434841, -0.275272048639511, 1.26239753050527, -0.000511224336925231, - 0.0095628568270856, -0.00397960092451418, 1.39587366293607e-05, 1.31409051361129e-05, - -9.83662017231755e-05, 1.87078667116619e-05}, - {27.168106989145, -2.43346872338192, 1.91135512970771, 0.0553180826818016, -0.0481878292619383, - 0.0052773235604729, -0.000428011927975304, 0.000528018208222772, -0.000285438191474895, - -5.71327627917386e-05}, - {-0.169494136517622, -0.350851545482921, 1.19922076033643, 0.0101120903675328, - -0.00151674465424115, 0.00548694086125656, -0.000108240000970513, 1.57202185024105e-05, - -9.77555098179959e-05, 2.09624089449761e-05}, - {-32.3807957489507, 1.8271436443167, 2.51530814328123, -0.0532334586403461, -0.0355980127727253, - -0.0213373892796204, 0.00045506092539885, 0.000545065581027688, 0.000141998709314758, - 0.000101051304611037}}; - susHandlingParameters.sus1orientationMatrix = {{0, 0, -1}, {-1, 0, 0}, {0, 1, 0}}; - susHandlingParameters.sus1coeffAlpha = { - {-27.6783250420482, -0.964805032861791, -0.503974297997131, -0.0446471081874084, - -0.048219538329297, 0.000958491361905381, -0.000290972187162876, -0.000657145721554176, - -0.000178087038629721, 4.09208968678946e-05}, - {2.24803085641869, 1.42938692406645, 0.30104994020693, 0.00756499999397385, 0.0117765927439368, - -0.000743685980641362, 4.69920803836194e-05, 0.000129815636957956, -9.10792250542345e-06, - -2.03870119873411e-05}, - {26.9943033817917, 0.147791175366868, -3.48256070200564, -0.0303332422478656, - 0.0183377266255394, 0.124593616125966, -0.000466003049304431, -0.000272000698791331, - -0.00063621309529853, -0.00158363678978767}, - {-0.221893380318465, 1.29919955307083, 0.21872487901019, 0.0049448219667127, - 0.00291224091529189, 0.00654651987282984, -9.86842469311185e-05, 8.20057454706638e-05, - 6.42331081725944e-05, 7.11656918299053e-05}, - {1.40178843964621, 1.1733111455249, 0.287485528779234, -0.000793970428759834, - 0.000170529273905818, -0.00268807864923086, 9.09553964483881e-05, -0.000271892733575409, - 8.52016306311741e-05, -0.000291797625433646}, - {0.65549617899457, 1.25716478394514, 0.301396415134214, -0.00357289640403958, - -0.000473416364133431, -0.010760332636205, -9.77220176481185e-05, 4.40798040046875e-05, - 2.84958344955681e-05, 0.000128583400693359}, - {6.20958048145025, 1.9528406481596, 1.32915657614139, -0.0326944423378284, -0.0158258335207969, - 0.0328249756354635, 0.00027113042931131, -0.000133980867173428, -0.000357964552318811, - 0.000224235061786191}, - {2.46222812180944, 1.1731834908026, 0.17440330925151, -0.00132279581980401, - -0.00447202005426964, -0.000804321602550913, -1.59526570766446e-05, 2.62946483533391e-05, - 3.28466749016414e-05, -6.63837547601294e-06}, - {42.615758859473, 2.46617281707273, -5.742515881283, -0.131942799763164, 0.20250702826603, - 0.0981562802911027, 0.00189939440077981, -0.0018591621618441, -0.00161121179693977, - -0.00058814458116749}}; - susHandlingParameters.sus1coeffBeta = { - {-12.300032617206, -1.06640894101328, 0.33950802247214, -0.00890867870617722, -0.04872758086642, - -0.0114263851027856, 0.000141061196404012, -0.000675469545483099, -0.000138249928781575, - -0.000138871036200597}, - {10.1631114109768, 0.261654603839785, 1.2376413405181, 0.00888558138614535, 0.00151674939001532, - -0.00534577602313027, 9.19430013005559e-05, 5.39804599087081e-05, -4.15760162347772e-05, - -7.60797902457032e-05}, - {-30.142329062199, 1.26939195100229, 6.14467186367471, 0.0464163689935328, 0.00379001947505376, - -0.165444163648109, 0.000516545385538741, 1.56053219154647e-05, -5.58651971370719e-05, - 0.00173185063955313}, - {12.1454103989862, -0.243589095509132, 2.02543716988677, -0.000857989774598331, - -0.00705278543432513, 0.0250580538307654, 3.50683653081847e-05, -2.63093897408875e-05, - -5.67352645830913e-05, 0.000232270832022029}, - {4.4338108906594, -0.305276965994378, 1.17293558142526, 0.000152618994429577, - 0.00134432642920902, -0.00104036813342885, 0.000334476082056995, 6.74826804343671e-05, - 0.000275311897725414, 7.58157740577916e-05}, - {3.47680700379043, -0.154163381023597, 1.389579838768, 0.000799705880026268, - 0.00401980026462874, -0.00915311817354667, -2.54817301605075e-06, -2.27422984169921e-05, - -2.61224817848938e-05, 6.00381132540332e-05}, - {29.469181543703, -0.722888948550437, 3.3623377135197, 0.00148445490093232, -0.0474780142430845, - 0.0486755575785462, 0.000126295091963757, 0.000526632230895258, -0.000259305985126003, - 0.000412751148048724}, - {2.67029041722834, -0.0837968038501666, 1.37628504937018, 0.00165061312885753, - -0.00953813055064273, 0.0032433005486936, -1.6522452172598e-05, 0.000144574078261271, - -8.47348746872376e-05, -1.92509604512729e-06}, - {-20.959201441285, -2.23605897639125, 5.73044624806043, 0.0354141964763815, 0.0887545371234514, - -0.193862330062381, 0.000216532998121618, -0.00207707610520973, 0.000552928905346826, - 0.00190182163597828}}; - susHandlingParameters.sus2orientationMatrix = {{-1, 0, 0}, {0, 0, -1}, {0, -1, 0}}; - susHandlingParameters.sus2coeffAlpha = { - {6.51602979328333, 0.690575501042577, 1.18185457002269, -0.0153161662266588, - 0.00145972227341484, 0.0351496474730776, -0.000172645571366945, -6.04213053580018e-05, - 9.74494676304114e-05, 0.000334122888261002}, - {0.954398509323963, 1.10996214782069, 0.313314231563221, -0.00367553051112208, - 0.0110290193380194, 0.000240079475656232, -6.93444423181303e-05, 0.000107433381295167, - 1.30750132315838e-05, -2.43580795300515e-05}, - {-55.1159841655056, -1.47449655191106, 3.40106264596874, -0.0621428271456258, - 0.0659788065633613, -0.0791732068323335, -0.000524264070592741, 0.000582093651418709, - -0.000586102213707195, 0.000658133691098817}, - {1.98614148820353, 1.32058724763677, 0.156843003413303, 0.002748082456053, 0.00202677073171519, - 0.00382360695862248, -0.000122364309010211, 5.33354637965168e-05, 3.93641210098335e-05, - 4.06398431916703e-05}, - {3.41223117010734, 1.1597568029329, 0.31881674291653, -0.000382400010917784, - -0.000754945672515052, -0.00079200882313927, 0.000145713118224563, -0.00026910957285589, - 0.000137876961532787, -0.000326798596746712}, - {6.23333031852853, 1.24902998148103, -0.0162317540018123, -0.00338184464699201, - 0.000420329743164687, 0.00202038442335185, -7.10435889754986e-05, -6.04039458988991e-06, - 7.25318569569788e-06, -2.5930447720704e-05}, - {191.759784636909, -10.5228276216193, 8.48306234734519, 0.243240262512846, -0.344226468125615, - 0.126267158197535, -0.00186612281541009, 0.00304415728817747, -0.00304958575196089, - 0.000457236034569107}, - {5.61375025356727, 1.1692295110657, 0.224665256727786, -0.00230481633344849, - -0.00746693012026367, -0.00172583925345173, -7.00823444553058e-06, 7.31362778266959e-05, - 5.81988007269583e-05, 1.3723604109425e-05}, - {98.0250669452855, -2.18500123986039, -6.68238707939385, 0.000754807832106659, - 0.256133336978808, 0.110826583415768, 0.000457663127670018, -0.00197655629847616, - -0.00254305206375073, -0.000466731538082995}}; - susHandlingParameters.sus2coeffBeta = { - {41.1102358678699, 2.3034699186519, 2.74551448799899, 0.061701310929235, 0.0317074142089495, - 0.0308171492962288, 0.00049453042200054, 0.000519222896270701, 2.85420168881716e-05, - 0.000259197384126413}, - {4.46821725251333, 0.0125273331991983, 1.32640678842532, 0.000543566569079156, - 0.00396616601484022, -0.00488408099728387, -3.05734704054868e-06, 7.3424831303621e-05, - -5.49439160235527e-05, -8.30708110469922e-05}, - {64.773396165255, 2.97057686090134, -1.90770757709096, 0.062747116236773, -0.077990648565002, - 0.0613989204238974, 0.00055512113297293, -0.000347045533958329, 0.00104059576098392, - -0.000348638726253297}, - {3.10352939390402, -0.2376108554276, 1.60523925160222, 0.00116454605680723, -0.0067958260462381, - 0.0136561370875238, 2.59929059167486e-05, 3.33825895937897e-05, -5.55828531601728e-05, - 0.000109833374761172}, - {0.156052891975873, -0.320721597024578, 1.15208488414874, 0.00164743688819939, - 0.000534718891498932, 0.000469870758457642, 0.000308432468885207, 0.00011789470679678, - 0.000292373398965513, 0.000183599033441813}, - {2.84967971406268, -0.21374251183113, 1.09938586447269, 2.34894704600407e-05, - 0.00588345375399262, 0.00296966835738407, 8.42707308834155e-06, 2.81870099202641e-06, - -3.56732787246631e-05, -7.04534663356379e-05}, - {-7.59892007483895, 0.358662160515702, 0.805137646978357, 0.00222144376998348, - 0.0464438387809707, 0.00847551828841782, 3.24805702347551e-05, 5.45500807838332e-05, - 0.000941378089367713, 0.000353137737023192}, - {-4.65367165487109, 0.201306010390421, 1.19135575710523, -0.00692801521395975, - 0.00394118754078443, 0.00426360093528599, 6.297683536736e-05, -7.15794236895102e-05, - -7.47076172176468e-05, -1.94516917836346e-05}, - {-59.5882618930651, 3.84530212586425, 3.50497032358686, -0.116100453177197, -0.0380997421813177, - -0.0581898335691109, 0.00111464935006159, 0.000559313074537689, 0.000168067749764069, - 0.000563224178849256}}; - susHandlingParameters.sus3orientationMatrix = {{1, 0, 0}, {0, 0, 1}, {0, -1, 0}}; - susHandlingParameters.sus3coeffAlpha = { - {-174.687021034355, -7.53454036765748, -9.33798316371397, -0.18212338430986, -0.242523652239734, - -0.202086838965846, -0.00138648793335223, -0.00225430176012882, -0.00198887215340364, - -0.00160678535160774}, - {6.92009692410602, 1.8192037428209, 0.254908171908415, 0.0179273243472017, 0.00894059238779664, - -0.000436952529644, 0.000138070523903458, 9.22759645920339e-05, -9.4312261303588e-06, - -1.76647897892869e-05}, - {-17.9720006944368, 0.230510201259892, 1.10751755772907, -0.00973621304161327, - 0.0554450499198677, -0.00590970792122449, -2.92393772526592e-05, 0.000444329929586969, - -0.000436055839773919, -9.5869891049503e-05}, - {-4.9880829382985, 1.33627775121504, -0.330382157073243, 0.00306744056311184, - 0.00376353074674973, -0.0107453978169225, -0.00010680477021693, 5.17225535432745e-05, - 7.4423443938376e-05, -0.000107927900087035}, - {0.952867982900728, 1.14513280899596, 0.307744203675505, 0.000404669974219378, - -0.000737988606997615, 0.00120218232577844, 0.000191147653645603, -0.000275058867995882, - 0.000137187356620739, -0.000320202731145004}, - {8.076706574364, 1.31338618710295, -0.334634356394277, -0.00209719438033295, - -0.00381753503582303, 0.0100347823323616, -7.00550548221671e-05, -1.97626956996069e-05, - 7.80079707003333e-05, -8.95904360920744e-05}, - {-82.4748312650249, 8.63074484663009, -0.949295700187556, -0.178618807265278, 0.130143669167547, - 0.0284326533865768, 0.00149831261351137, -0.0011583692969717, 0.0010560778729661, - 0.000635404380970666}, - {3.34457857521978, 1.09242517408071, 0.241722402244944, 0.00381629887587041, - -0.00863580122530851, 0.00137050492069702, -8.91046701171713e-05, 8.44169683308007e-05, - -3.54608413548779e-05, 8.54042677832451e-06}, - {78.1540457908649, -1.30266922193303, -5.33605443700115, 0.0184226131926499, 0.146629920899062, - 0.110698519952472, 6.64041537651749e-05, -0.00120174584530713, -0.00133177694921411, - -0.000796422644338886}}; - susHandlingParameters.sus3coeffBeta = { - {-31.5704266802979, -5.10700699133189, 2.84549700473812, -0.122701561048957, -0.11257100034746, - 0.102120576206517, -0.000796645106694696, -0.00192211266325167, -4.99981232866237e-05, - 0.00104036677004523}, - {-0.734294938181273, -0.0694317595592039, 1.34746975389878, -0.00103465544451119, - 0.00389798465946559, -0.00308561832194191, -2.91843250099708e-06, 7.59634622232999e-05, - -6.54571602919161e-05, -0.000104146832644606}, - {24.2649069708536, 3.08145095664586, 1.88975821636026, 0.0767528234206466, -0.0526971951753399, - -0.0477053831942802, 0.000613806533422364, -0.000631628059238499, 0.00026217621127941, - 0.000555307997961608}, - {0.62884078560034, -0.152668817824194, 1.70304497205574, 0.000894387499536142, - -0.00306495168098874, 0.0180087418010658, 1.74990847586174e-05, 3.1263263531046e-05, - -7.1643235604579e-06, 0.000147876621100347}, - {-3.05400297018165, -0.316256447664344, 1.14841722699638, 0.000671621084688467, - -0.000906765726598906, 0.000687041032077189, 0.000323419818039841, 0.000128019308781935, - 0.000286018723737538, 0.000192248693306256}, - {-4.39855066935163, -0.322858945262125, 1.44405016355615, -4.93181749911261e-05, - 0.0127396834052722, -0.00523149676786941, 2.56561922352657e-05, 7.61202764874326e-06, - -0.00014623717850039, 8.12219846932013e-06}, - {110.820397525173, -10.9497307382094, 2.48939759290446, 0.296585618718034, -0.142611297893517, - -0.0141810186612052, -0.00275127095595919, 0.00160686698368569, -0.000872029428758877, - -0.000410522437887563}, - {-7.15740446281205, 0.104233532313688, 1.13155893729292, -0.00350418544400852, - 0.00532058598508803, 0.00459314980222008, 3.09155436939349e-05, -7.60935741692174e-05, - -5.87922606348196e-05, 2.56146268588382e-05}, - {44.8818060495112, -7.94729992210875, 3.59286389225051, 0.217944601088562, 0.108087933176612, - -0.116711715153385, -0.00194260120960441, -0.0015752762498594, -0.000331129410732722, - 0.00125896996438418}}; - susHandlingParameters.sus4orientationMatrix = {{0, -1, 0}, {1, 0, 0}, {0, 0, 1}}; - susHandlingParameters.sus4coeffAlpha = { - {-12.4581187126738, 0.398038572289047, -0.438887880988151, -0.00965382887938283, - -0.0309322349328842, -0.00359106522420111, -7.79546112299913e-06, -0.000432733997178497, - -9.79031907635314e-05, -1.49299384451257e-05}, - {8.41054378583447, 1.87462327360707, 0.266809999719952, 0.0216455385250676, 0.00879426079919981, - -0.00142295319820553, 0.000194819780653264, 8.57549705064449e-05, -3.56478452552367e-05, - -1.65680920554434e-05}, - {16.4141780945815, 2.57697842088604, 0.373972171754278, 0.0498264199400303, 0.0183175817756131, - -0.008545409848878, 0.000422696533006382, -0.000268245978898508, -0.000663188021815416, - -7.51144017137827e-05}, - {0.796692054977593, 1.26773229735266, 0.247715261673662, 0.00358183885438128, - 0.00216435175662881, 0.00713732829335305, -0.000110129715615857, 3.56051594182427e-05, - 5.03074365340535e-05, 8.40279146176271e-05}, - {2.37491588500165, 1.05997969088519, 0.309540461340971, -0.000405047711742513, - 0.000462224730316111, -0.00201887171945793, 0.000260159805167265, -0.000282867209803598, - 0.000201613303652666, -0.000277796442847579}, - {6.36749007598708, 1.31659760017973, -0.122724934153231, -0.00328808937096891, - -0.00577347207798776, 0.00403172074457999, -7.45676459772001e-05, 1.79838644222274e-05, - 0.000104552066440564, -2.78115121929346e-05}, - {-47.9667098848496, 3.97703197139796, -1.96403894754299, -0.0577989657406978, - 0.0634225576208007, -0.0346023445055141, 0.00045886475369098, -0.000326132951996844, - 0.000716490441845967, -0.000136132038635483}, - {6.21505474256094, 0.871830486201601, 0.286906473833627, 0.007875292606045, - -0.00974634725746389, 0.00128416935792136, -0.000111796743751489, 0.000102016719989187, - -3.3503088289589e-05, -1.03874407813931e-05}, - {102.09801265482, -4.12715152309748, -5.04594403360339, 0.075499959116996, 0.216574192561683, - 0.0750031215784663, -0.000147358932612646, -0.0023710703422108, -0.00143310719642393, - -0.000431914403446768}}; - susHandlingParameters.sus4coeffBeta = { - {-21.5077132684032, -1.60004839699939, -0.0298995033958561, -0.0315563250430659, - -0.0424403625879891, -0.0245426225510417, -0.000209861203016225, -0.000422150973104431, - -0.00030514398458781, -0.000211986731019738}, - {9.07644247897601, 0.207457289788099, 1.26735366597312, 0.00768477352180427, - 0.00429230749575816, -0.00514802326062087, 7.56149591998578e-05, 8.42794730840662e-05, - -3.62215715492783e-05, -5.24384190165239e-05}, - {-33.5225408043693, -3.11167857248829, 1.91760591695775, -0.0963752386435729, - 0.00026620241534153, -0.0256680391021823, -0.00102188712837393, 2.63753563968978e-05, - 0.000113172463974702, 0.000271939918507175}, - {19.1379025029401, -0.225979661987912, 2.72337120022998, -0.00136982412154458, - -0.00447301210555274, 0.046496718064139, 2.09123846958985e-05, -4.30383094864847e-05, - -1.22808643520768e-05, 0.000440555709696048}, - {2.957867714783, -0.316069593806939, 1.06379930645214, 0.00103244713047271, 0.00148059212230411, - 0.000557885068990542, 0.000288633931072557, 0.000172775380291659, 0.000269738457990237, - 0.000254577019084984}, - {2.04155199929521, -0.318303488378033, 1.37820715117028, 0.00114788656817743, - 0.0130051117909245, -0.00743109928493789, 1.22403390396844e-05, -3.19245785131217e-05, - -0.000156735218010879, 3.81458400945988e-05}, - {27.314954181241, -1.43916155634084, 2.48967706992348, 0.0278695408478388, -0.0341141456915131, - 0.0281959785297513, -0.000252996164135396, 0.000163365679366542, -0.000380129463154642, - 0.000159350154429114}, - {-0.274693278266294, 0.0199711721436635, 1.26676843352524, -0.0006713759238817, - -0.00389715205101059, 0.00294298337610857, -9.58643121413979e-06, 6.30700938550725e-05, - -6.07188867796123e-05, 7.72199861279611e-06}, - {-74.1601853968901, 2.55641628908672, 6.38533530714782, -0.0582345132980647, - -0.0653804553172819, -0.138850555683872, 0.000489364157827405, 0.000469559629292745, - 0.000698140692952438, 0.00123017528239406}}; - susHandlingParameters.sus5orientationMatrix = {{1, 0, 0}, {0, -1, 0}, {0, 0, -1}}; - susHandlingParameters.sus5coeffAlpha = { - {-12.1398741236355, 1.99425442858125, -1.9303044815802, 0.0418421279520049, -0.0309683799946315, - -0.0562201123081437, 0.000522607299552916, -0.000375386573815007, -0.000183899715035788, - -0.000600349486293698}, - {4.51862054729553, 1.72396080253297, 0.274562680698765, 0.0162681383591035, 0.0108410181586673, - -0.000272215427359511, 0.000124164068046579, 0.000125586897851351, -1.24082224214974e-05, - -1.63339067540159e-05}, - {63.0100748193658, 7.78014670478172, 0.327263471268564, 0.181264302704374, -0.0652454854214506, - -0.03906716801285, 0.00166924078925478, -0.000749939315526625, 0.000320696101132374, - 0.000499934751180042}, - {-2.14377722994325, 1.33617641673436, 0.0973465660282871, 0.00389526886867845, - 0.00526064997381395, 0.00244964888333519, -8.59416490903541e-05, 4.58871931007681e-05, - 8.6123353128647e-05, 2.85447259858337e-05}, - {0.164792977301912, 1.17541977248641, 0.348838798760518, -0.000180865118417534, - 0.000331789515553421, -0.000734333865631793, 9.76677859410759e-05, -0.000324347075049525, - 8.66683396011167e-05, -0.000385839566009832}, - {-0.228934187493575, 1.30552820143752, 0.306779576899158, -0.00508763741184706, - -0.00318524263093038, -0.00878095392529144, -6.59040013073836e-05, 8.69122529321691e-05, - 5.73853071731283e-05, 8.56628414466758e-05}, - {22.6047744510684, -0.591739857860868, 0.566728856847393, 0.0498124268150265, - -0.0214126910277926, 0.00538091942017912, -0.000391517685229849, 0.000554321668236216, - 0.000191004410219065, 0.000102775124022018}, - {4.54704081104052, 0.844841244606025, 0.181355971462193, 0.0109743851006749, - -0.00363467884122547, 0.00108873046814694, -0.000153236888951059, 3.14623342713789e-06, - -2.78503202185463e-05, 3.99983788680736e-06}, - {-30.878359404848, 5.20536009886854, -0.674455093700773, -0.10801865891189, -0.0514805639475938, - 0.0503660452068572, 0.00072776817295273, 0.00120288537038655, -0.000301602375634166, - -0.000477098479809266}}; - susHandlingParameters.sus5coeffBeta = { - {16.8155737032787, 0.65475660868259, 1.95532810363711, 0.000295624718662669, 0.0426379914736747, - 0.00192544771588337, -4.94534888281508e-05, 8.32299142575155e-05, 0.000645497238623369, - -0.000234155227840799}, - {9.48268090632318, 0.528942263930744, 1.34030963800712, 0.0173605129814363, 0.00581086655972212, - -0.00365006277801141, 0.000180048140973223, 0.000102002650672644, -4.10833110241736e-05, - -8.7810396165556e-05}, - {-47.8325489165383, -4.78262055949503, 1.66912859871505, -0.143518014673292, 0.0288441527062856, - -0.00322823115861497, -0.00148509910480755, 0.000284265179004289, -0.000175299737313045, - -7.04175618676909e-05}, - {3.70510151312723, -0.272200626024415, 1.5527519845099, 0.000589727630962265, - -0.00889682554869096, 0.0109857452472628, 3.05876215574877e-05, 2.09194236165814e-05, - -8.33769024439277e-05, 6.90991113575066e-05}, - {0.820199776906695, -0.355683467192776, 1.17142130858009, -0.000160174871610729, - 4.09723480153701e-05, 0.000209103751629257, 0.000390331989170637, 6.45642836249667e-05, - 0.000318092703362044, 0.000107158633760141}, - {5.52084497768914, -0.227775345312466, 0.845897282556327, 0.00157426476122436, - 0.00657189797805861, 0.0103797665963117, 2.51479848048895e-05, -4.78371400399983e-05, - -5.20221896473413e-05, -0.000143840492906166}, - {-33.4875689683454, 0.937557276329106, -1.02741065470967, -0.0140023273976314, - 0.0401908729477037, -0.0512457211360142, 7.05537967426573e-05, -0.00027521752411122, - 0.000407657552700476, -0.000458411000693613}, - {0.931346887326171, -0.320804452025793, 1.28866325376154, 0.00912456151698805, - -0.00404367403569981, 0.00477543659981282, -9.43987917474817e-05, 4.66464249533497e-05, - -7.89362487264572e-05, -1.0951496495443e-05}, - {-38.3689359928435, 3.8540516906071, 1.26391725545116, -0.108584643500539, -0.0542697403292778, - 0.0285360568428252, 0.000845084580479371, 0.00114184315411245, -0.000169538153750085, - -0.000336529204350355}}; - susHandlingParameters.sus6orientationMatrix = {{0, 0, 1}, {1, 0, 0}, {0, 1, 0}}; - susHandlingParameters.sus6coeffAlpha = { - {13.0465222152293, 0.0639132159808454, 2.98083557560227, -0.0773202212713293, - 0.0949075412003712, 0.0503055998355815, -0.00104133434256204, 0.000633099036136146, - 0.00091428505258307, 0.000259857066722932}, - {1.66740227859888, 1.55804368674744, 0.209274741749388, 0.0123798418560859, 0.00724950517167516, - -0.000577445375457582, 8.94374551545955e-05, 6.94513586221567e-05, -1.06065583714065e-05, - -1.43899892666699e-05}, - {8.71610925597519, 1.42112818752419, -0.549859300501301, 0.0374581774684577, 0.0617635595955198, - 0.0447491072679598, 0.00069998577106559, 0.00101018723225412, -4.88501228194031e-06, - -0.000434861113274231}, - {-2.3555601314395, 1.29430213886389, 0.179499593411187, 0.00440896450927253, - 0.00352052300927628, 0.00434187143967281, -9.66615195654703e-05, 3.64923075694275e-05, - 6.09619017310129e-05, 4.23908862836885e-05}, - {-0.858019663974047, 1.10138705956076, 0.278789852526915, -0.000199798507752607, - 0.00112092406838628, -0.00177346866231588, 0.000217816070307086, -0.000240713988238257, - 0.000150795563555828, -0.000279246491927943}, - {7.93661480471297, 1.33902098855997, -0.64010306493848, -0.00307944184518557, - -0.00511421127083497, 0.0204008636376403, -9.50042323904954e-05, 6.01530207062221e-05, - 9.13233708460098e-05, -0.000206717750924323}, - {16.2658124154565, 0.191301571705827, 1.02390350838635, 0.0258487436355216, -0.0219752092833362, - 0.0236916776412211, -0.000350496453661261, -0.000123849795280597, -0.000532190902882765, - 9.36018171121253e-05}, - {-1.53023612303052, 1.29132951637076, 0.181159073530008, -0.0023490608317645, - -0.00370741703297037, -0.000229071300377431, -1.6634455407558e-05, 1.11387154630828e-05, - 1.02609175615251e-05, -9.64717658954667e-06}, - {-32.9918791079688, 0.093536793089853, 4.76858627395571, 0.0595845684553358, -0.054845749101257, - -0.133247382500001, -0.000688999201915199, 7.67286265747961e-05, 0.000868163357631254, - 0.00120099606910313}}; - susHandlingParameters.sus6coeffBeta = { - {12.7380220453847, -0.6087309901836, 2.60957722462363, -0.0415319939920917, 0.0444944768824276, - 0.0223231464060241, -0.000421503508733887, -9.39560038638717e-05, 0.000821479971871302, - -4.5330528329465e-05}, - {1.96846333975847, -0.33921438143463, 1.23957110477613, -0.00948832495296823, - 0.00107211134687287, -0.00410820045700199, -9.33679611473279e-05, 3.72984782145427e-05, - -4.04514487800062e-05, -7.6296149087237e-05}, - {5.7454444934481, -1.58476383793609, -0.418479494289251, -0.0985177320630941, - -0.0862179276808015, 0.0126762052037897, -0.00118207758271301, -0.000190361442918412, - 0.0011723869613426, 0.000122882034141316}, - {2.11042287406433, -0.225942746245056, 1.18084080712528, -0.00103013931607172, - -0.00675606790663387, -0.00106646109062746, 1.7708839355979e-05, -3.13642668374253e-05, - -5.87601932564404e-05, -3.92033314627704e-05}, - {2.96049248725882, -0.286261455028255, 1.09122556181319, -0.000672369023155898, - 0.000574446975796023, 0.000120303729680796, 0.000292285799270644, 0.000170497873487264, - 0.000259925974231328, 0.000222437797823852}, - {1.65218061201483, -0.19535446105784, 1.39609640918411, 0.000961524354787167, - 0.00592400381724333, -0.0078500192096718, -7.02791628080906e-07, -2.07197580883822e-05, - -4.33518182614169e-05, 4.66993119419691e-05}, - {-19.56673237415, 1.06558565338761, 0.151160448373445, -0.0252628659378108, 0.0281230551050938, - -0.0217328869907185, 0.000241309440918385, -0.000116449585258429, 0.000401546410974577, - -0.000147563886502726}, - {1.56167171538684, -0.155299366654736, 1.20084049723279, 0.00457348893890231, - 0.00118888040006052, 0.0029920178735941, -5.583448120596e-05, -2.34496315691865e-05, - -5.3309466243918e-05, 6.20289310356821e-06}, - {1.95050549495182, -2.74909818412705, 3.80268788018641, 0.0629242254381785, 0.0581479035315726, - -0.111361283351269, -0.00047845777495158, -0.00075354297736741, -0.000186887396585446, - 0.00119710704771344}}; - susHandlingParameters.sus7orientationMatrix = {{0, 0, -1}, {-1, 0, 0}, {0, 1, 0}}; - susHandlingParameters.sus7coeffAlpha = { - {-92.1126183408754, -3.77261746189525, -4.50604668349213, -0.0909560776043523, - -0.15646903318971, -0.0766293642415356, -0.00059452135473577, -0.00144790037129283, - -0.00119021101127241, -0.000460110780350978}, - {1.60822506792345, 1.12993931449931, 0.300781032865641, -0.00405149856360946, - 0.0116663280665617, -0.000746071920075153, -8.36092173253351e-05, 0.000126762041147563, - -1.57820750462019e-05, -2.13840141586661e-05}, - {-151.403952985468, -5.77049222793992, 9.71132757422642, -0.113259116970462, 0.284142453949027, - -0.198625061659164, -0.000836450164210354, 0.00174062771509636, -0.00323746390757859, - 0.00124721932086258}, - {3.47391964888809, 1.28788318973591, 0.358380140281919, 0.0033863520864927, 0.00154601909793475, - 0.0103457296050314, -9.56426572270873e-05, 5.48838958555808e-05, 2.97537427220847e-05, - 0.000104735911514185}, - {3.32650947866065, 1.16701012685798, 0.293514063672376, -0.00065850791542434, - -8.61746510464303e-05, -0.00212038990772211, 0.00010377123197, -0.000262818127593837, - 0.000103360882478383, -0.000296739688930329}, - {-0.440176043435378, 1.18923278867097, 0.519516382652818, -0.00138846714677511, - 0.00266491699926247, -0.014254675949624, -4.20279929822439e-05, -5.49260281515447e-05, - -1.00328708454487e-05, 0.000138142092498215}, - {9.54962966738358, 1.83809145920811, 1.82162819067959, -0.0116786627338505, - -0.00496037444422313, 0.0590883547819332, 7.48465315787857e-05, 0.000221693951602584, - 7.96466345174136e-06, 0.000638822537725177}, - {7.04862901290925, 0.876813777672465, 0.16368093989381, 0.00928717461441627, - -0.00276538956293246, 0.00117995419940653, -0.000141511492474493, -6.09796031786385e-06, - -2.62114930414747e-05, -2.88713611443788e-06}, - {135.349147631811, -7.21933296299596, -6.02379024934871, 0.19557354282067, 0.207680233512614, - 0.12880101618361, -0.00169832076532024, -0.00192216719797732, -0.00188763612041332, - -0.00103101801961442}}; - susHandlingParameters.sus7coeffBeta = { - {-12.7115487367622, -1.08890790360556, 0.0579616268854079, -0.0212303293514951, - -0.0395948453851818, -0.0275564242614342, -0.000228652851842222, -0.000148106159109458, - -0.000555136649469199, -0.000198260004582737}, - {-0.988147625946871, -0.759018567468546, 1.20998292002818, -0.0241231836977845, - -0.000572110443300516, -0.00294835038249426, -0.00026533039022186, 6.82250069765274e-06, - 7.21038415209318e-06, -6.54881435118179e-05}, - {98.0979345921564, 4.27381413621355, -4.39956005193548, 0.0709109587666745, -0.172774236139236, - 0.107243391488741, 0.000421832640471043, -0.00140450884710288, 0.00158019019392239, - -0.00078512547169536}, - {4.10892685652543, -0.229301778557857, 1.33380992987117, -0.000250095848720304, - -0.00555205065514645, 0.00355052914398176, 1.62727119770752e-05, -1.26026527654764e-05, - -3.25505031810898e-05, 5.79970895921158e-06}, - {3.09432502337258, -0.300556003790433, 1.17085811008124, 0.00128679594824324, - 0.00148229981422985, 9.15267474159147e-05, 0.000300497843413856, 6.31378865575566e-05, - 0.000258447032558814, 9.79142983264352e-05}, - {8.92336134924575, -0.197306981784312, 0.659908505354084, 0.00175572239373996, - 0.006801023678097, 0.0189775987436792, 9.2187857727721e-06, -4.8706332690626e-05, - -6.887009887486e-05, -0.000266455617735054}, - {-52.0734887320227, 2.64822385560272, -1.72387600304694, -0.0383944891609251, 0.110873671161269, - -0.0475247245070445, 0.000194652401328063, -0.000697307928990137, 0.00124021816001, - -0.000194213899980878}, - {2.08203985879155, -0.127503525368396, 1.17628056094647, 0.00283288065938444, - 0.00394668214608305, 0.00314868636161131, -2.99504350569853e-05, -7.11070816314279e-05, - -6.30148122529749e-05, 2.28114298989664e-05}, - {191.321181158032, -12.2449557187473, -7.21933741885107, 0.267954293388644, 0.331529493933124, - 0.149867703984027, -0.00222279201444128, -0.00284724570619954, -0.00298774060233964, - -0.000988903783752156}}; - susHandlingParameters.sus8orientationMatrix = {{-1, 0, 0}, {0, 0, -1}, {0, -1, 0}}; - susHandlingParameters.sus8coeffAlpha = { - {5.46354311880959, 1.15370126035432, 0.568432485840475, -0.00105094692478431, - -0.000472899673842554, 0.015581320536192, 2.26460844314248e-05, -0.000254397947062058, - 0.000198938007250408, 0.000102026690279006}, - {8.8976133108173, 1.89502416095352, 0.268670471819199, 0.0217013413241972, 0.00973925295182384, - -0.00116357269193765, 0.000185865842232419, 0.000103311614912702, -2.46539447920969e-05, - -2.06292928734686e-05}, - {-45.4550803910752, 1.27220123406993, 5.21483855848504, 0.0315791081623634, 0.0725172355124129, - -0.13947591535243, 0.000412577580637848, 0.000434545096994917, -0.000840043932292312, - 0.00126857487044307}, - {1.81302768546433, 1.20563501267535, 0.344815267182167, 0.00546879453241056, - -0.00115382996865884, 0.010597876132341, -7.75885604486581e-05, 8.99568815949154e-05, - -2.98129544974679e-06, 0.000108913239345604}, - {2.19111439539173, 1.06951675598148, 0.283707798607213, 0.00016478588207518, - 0.000196086067268121, -0.00214980231173703, 0.000237820475654357, -0.000256402967908595, - 0.000165966620658577, -0.000268394081675921}, - {15.0858674915897, 1.27922724811168, -1.0803137812576, -0.00184009775302466, - -0.00458792284209219, 0.0359393555418547, -6.05121024079603e-05, -1.2288384024143e-05, - 8.55484605384438e-05, -0.000379241348638065}, - {-14.9594190080906, 1.79473182195746, -1.00830704063572, 0.000890685410857856, - 0.0408932029176081, -0.0165460857151619, -0.000170544299916973, -0.000370901607010145, - 0.000324089709129097, -9.33010240878062e-05}, - {0.867614491733251, 1.38248194737027, 0.233408537422123, -0.00772942878114575, - -0.00783126068079782, -0.000413713955432221, 4.5775750146291e-05, 6.97323029940275e-05, - 1.70664456940787e-05, 6.75517901233086e-06}, - {2.34474364146174, -0.777275400251477, 2.09531381577911, 0.0170780716714389, 0.102855060371092, - -0.1203441505925, 0.000187004964420911, -0.00141720441050986, -0.000336251285258365, - 0.00145175125888695}}; - susHandlingParameters.sus8coeffBeta = { - {28.3033101237397, 1.77504446792811, 1.70758838986317, 0.0307800697044683, 0.0598759344275936, - -0.014461432284373, 0.000128415617799076, 0.000664419128546701, 0.000312923304130995, - -0.000269026446641855}, - {7.73040563051023, 0.0267291479555493, 1.16189582308493, 0.000611047892976521, - -0.00213680506915073, -0.00517435586596902, -3.60304406049766e-06, -1.74452976404459e-05, - -3.95396925228538e-05, -7.01948519410633e-05}, - {-48.0766126130725, -3.77981206700298, 3.03482861087335, -0.0678496412519532, 0.115260678424016, - -0.0109681510065038, -0.000438011443691466, 0.00097230136258486, -0.000930875177732769, - -0.000203144239955507}, - {12.1881935626341, -0.234345089308583, 2.01134619426134, 0.000181529284001169, - -0.00642848065105061, 0.0243985799415726, 2.0224042581776e-05, 5.22503286757285e-06, - -4.75196303016323e-05, 0.000221160482364556}, - {3.49559433498742, -0.294995112674766, 1.07892379698257, 0.000861664794052587, - 0.00138978933062055, 0.000436385106465176, 0.000288095124755908, 0.000147259769247883, - 0.000256686898599516, 0.000198982412957039}, - {9.36663996178607, -0.171266136751803, 0.799869891484541, -0.000896305696610864, - 0.00477919972789653, 0.0077876110326094, 9.16475263625076e-06, 3.02461250100473e-05, - -3.63917701783264e-05, -0.000101376940843402}, - {9.93372683055145, 1.02056557854246, 3.01635426591734, -0.0477113881140277, -0.0280426434406976, - 0.0438813017696874, 0.000470431190169998, -7.55753674679743e-05, -0.000516444906323815, - 0.000253844418223843}, - {4.12868774589741, -0.305711790187688, 1.15739216407191, 0.00942395115281056, - 0.00264758462357433, 0.00227985850688479, -0.000107537164019682, -4.91396736189963e-05, - -5.3803493814502e-05, 6.80587059728718e-06}, - {64.9193383444005, -1.57724255547465, -3.82166532626293, 0.0104712238987591, 0.0898786950946473, - 0.128910456296131, -8.27123227422217e-05, -0.000143979624107479, -0.00146684876653306, - -0.00102226799570239}}; - susHandlingParameters.sus9orientationMatrix = {{1, 0, 0}, {0, 0, 1}, {0, -1, 0}}; - susHandlingParameters.sus9coeffAlpha = { - {65.8975109449121, 2.19115342242175, 6.11069527811832, -0.0219884864133703, 0.119985456538482, - 0.142746712551924, -0.000465882328687976, 0.000606525132125852, 0.00141667074621881, - 0.00109715845894006}, - {5.70337356029945, 1.86705636976809, 0.235584190291708, 0.0194937327615426, 0.00973291465247784, - -0.00155675297510773, 0.000147099297988423, 0.000115708967219349, -4.1462310493722e-05, - -9.80097031103588e-06}, - {138.221145997284, 6.07665575619595, -9.08085914250542, 0.0839801072927519, -0.143071750033303, - 0.237868300719915, 0.000626693630444932, -0.000579788170871402, 0.00181740650944343, - -0.00207086879728281}, - {-7.78295582666151, 1.37506685179192, -0.507596181420042, 0.00350118305456038, - 0.00380814310115541, -0.0174012437563343, -0.000124801268056815, 2.96314830184492e-05, - 6.3416992450033e-05, -0.000190177262510221}, - {0.13102597129751, 1.24228303845143, 0.328808873447393, 2.6858679536165e-05, - 0.000231428138164498, -0.000584089095259736, 5.5322167970451e-05, -0.000322205709821716, - 7.71348293209208e-05, -0.000393885990364776}, - {4.64571633968935, 1.2668223691397, -0.158952088650432, -0.0038344859267428, 0.0030051503726095, - 0.00455578826025588, -9.42520993914957e-05, 5.81633314412289e-05, -4.43545804544095e-05, - -4.83524454851519e-05}, - {99.2385930314563, -3.65569343617926, 5.54203926675588, 0.0975630395981933, -0.15701634159692, - 0.107834711298836, -0.000885326636237814, 0.000960753844480462, -0.00179894024848343, - 0.000583066757644971}, - {2.82671549736619, 1.11214198870501, 0.214735318432744, 0.00284415167563662, - -0.00743289575690122, 0.000382705440762292, -7.43232442872501e-05, 6.96994098083348e-05, - -4.15108111710131e-06, 1.33520085213482e-05}, - {36.9013743125415, -0.522392401546163, -1.52452843963663, 0.0261375433218879, 0.060573568610239, - 0.0182582125221054, -0.000244373383911157, -0.000271385147292484, -0.000723799969427732, - 6.76324880239196e-05}}; - susHandlingParameters.sus9coeffBeta = { - {128.70886435409, 7.27355509732751, 7.18142203531244, 0.1536100459329, 0.199455846541636, - 0.101824964939793, 0.00116666116789421, 0.00181595584079788, 0.00159271319494017, - 0.000556768406475719}, - {-7.07933839681024, -0.979062424441878, 1.21792546815617, -0.0295740143783226, - -0.00442780611714201, -0.00329612819203176, -0.000291373125216143, -7.47259350176359e-05, - -4.87265282482212e-05, -7.87490350444332e-05}, - {41.1357193180502, 2.75138456414254, -0.0160889117718198, 0.0274001112562423, - -0.145644717742057, -0.0316076203283094, -0.000136443337244472, -0.00153945199081365, - 0.000938960439977633, 0.000599987111822885}, - {2.7980384746608, -0.234741037383589, 1.5342193016705, -0.000993791566721689, - -0.00787533639513478, 0.00927468655141365, 2.63308697896639e-05, -3.42816267184975e-05, - -8.48879419798771e-05, 3.84043821333798e-05}, - {0.427687530667804, -0.346076633694936, 1.22968527483851, -4.95098138311122e-05, - 0.000298245372198029, 0.000332756250024796, 0.00040375986210644, 5.20675972504572e-05, - 0.000327042170278218, 5.93011568264671e-05}, - {4.50337810133314, -0.279364254817202, 0.945812187846199, 0.000116182663432306, - 0.0115646046622083, 0.00908289960302886, 1.90394667311541e-05, -4.4360223646434e-06, - -0.000131398914898614, -0.000145568992865512}, - {-36.3377213654193, 2.21047221783626, 0.0609982245149821, -0.0670546774988572, - 0.016827777144747, -0.0277834084058314, 0.000778301409125556, 0.000135846745194401, - 0.00043261858797068, -0.00021172728254561}, - {-0.737678205841529, -0.217352122193475, 1.23494846329297, 0.00748173441779792, - 0.0019595873704705, 0.00567253723266176, -8.34768773292938e-05, -3.50608394184873e-05, - -0.000107500091550635, -5.1379722947632e-07}, - {-36.6150844777671, 3.24952006904945, 1.7222457840185, -0.0846362445435584, -0.0625549615377418, - 0.019178365782485, 0.000664877496455304, 0.000942971403881222, 0.000190754698755098, - -0.000372226659190439}}; - susHandlingParameters.sus10orientationMatrix = {{0, -1, 0}, {1, 0, 0}, {0, 0, 1}}; - susHandlingParameters.sus10coeffAlpha = { - {14.4562393748324, 0.669162330324919, 2.13895255446541, -0.0161997097021299, - 0.00185995785065838, 0.0621351118528379, -0.000278999272493087, 0.000238469666491965, - -0.000279407497782961, 0.000726904943739837}, - {-4.45678285887022, 0.92869611919737, 0.186752102727282, -0.00706160758952316, - 0.00532680276723634, -0.00119102617674229, -0.000105283880098953, 3.90673052334419e-05, - -3.13338277344246e-05, 5.32977236959767e-06}, - {30.4255268053197, 3.00991076401191, -1.4855621363519, 0.033934286288413, -0.0553588742704929, - 0.0299275582316466, 0.000167915322354466, -0.00050925078118232, 0.000463662961330962, - -0.000232919143454163}, - {2.45076465343337, 1.30206564388838, 0.635121046212765, 0.00517109639797675, - 0.00360579544364496, 0.0198490668911362, -9.31556816982662e-05, 6.7313653707875e-05, - 6.4669137025142e-05, 0.000209727581169138}, - {-0.784841314851562, 1.10058314980836, 0.314063830836532, 0.000583003703415889, - 0.000312635453606579, -0.000183738114552387, 0.000214096205760617, -0.000286744686021244, - 0.000159157597180407, -0.00032235099420715}, - {7.19568036510586, 1.33307479701657, -0.465585141952456, -0.0031910726544199, - -0.00546273504371797, 0.0145494754402526, -7.9863949693769e-05, 4.83681329120104e-05, - 8.85844309936609e-05, -0.000143217870916994}, - {-12.8344546267449, 1.36023633150143, -0.728527724854506, 0.019982118403416, 0.0385056413989437, - -0.00468598272326268, -0.000303957957649245, -6.37783846968216e-05, 0.000514049116643205, - 0.000112015427600697}, - {-2.58279031298065, 1.42167821629586, 0.208769467511292, -0.00640190372145885, - -0.0056405289717473, 0.000509611313918708, 2.23310562107823e-05, 3.23685469522147e-05, - -7.55982776243849e-06, 2.78417756661088e-06}, - {-29.7178996143914, 2.636972251183, 1.97316329325243, -0.03983524158327, -0.0193152048730234, - -0.0600902798379509, 0.00031786916010672, 0.000162178988605602, 0.000224550786416246, - 0.000614337977361927}}; - susHandlingParameters.sus10coeffBeta = { - {12.4771349792459, 1.44317849705414, 0.975637226331561, 0.0430284146301043, 0.0220810531548995, - -0.0220926906772, 0.000310052324529521, 0.000658151808869523, -0.000288026365111098, - -0.000214619731807045}, - {-0.113203260140131, -0.272424061092191, 1.27704377191184, -0.00791746619331075, - 0.00278646694862191, -0.00398881099259934, -8.09569694307212e-05, 5.99617384829016e-05, - -5.4550919751855e-05, -8.6314530565085e-05}, - {-48.585664295448, -2.04899787231903, 4.48757129623549, -0.0226180460431321, 0.090326735447661, - -0.0722998813632622, -6.77623771415477e-05, 0.000562585419036509, -0.000956171370931993, - 0.000491554402311223}, - {-1.20986884955482, -0.215604107185474, 1.22123198786617, 0.000256508527822089, - -0.00625056735692847, 0.00262961582224303, 2.27433984698861e-05, 1.60471509861372e-05, - -4.85061736834262e-05, -1.8387092782907e-06}, - {-0.250205907903409, -0.315819331560782, 1.09018364376391, -0.000521787614293089, - -0.000500747760913489, 2.48184307342838e-05, 0.000313799238640988, 0.000136669146368744, - 0.000278914324565192, 0.000218512838469476}, - {-1.38512578184076, -0.240456589364121, 1.34170304231345, 0.00017499230372669, - 0.0070862275911073, -0.00460640844814105, 1.27594111036696e-05, -4.73855624902052e-06, - -5.41141037812903e-05, 8.50767021818388e-06}, - {58.9917559342216, -2.28705697628345, 5.35995190407842, 0.0214721399750612, -0.112195722921667, - 0.0890150265857542, -0.000100675657768708, 0.000493488022135339, -0.00137672908303878, - 0.000518683157694955}, - {3.18905073365834, -0.633376549706314, 1.17190259811174, 0.0188817945597344, - 0.00107470708915782, 0.00400880471375267, -0.000197312295539118, -2.46543035998379e-05, - -6.07871064300252e-05, 1.91822310311955e-05}, - {-21.6881499304099, -0.563186103920008, 3.70747028664292, 0.021112883967427, - -0.00650020689049325, -0.0778533644688476, -0.000131921888670268, -0.000402754836445439, - 0.000551249824375055, 0.00062236627391337}}; - susHandlingParameters.sus11orientationMatrix = {{1, 0, 0}, {0, -1, 0}, {0, 0, -1}}; - susHandlingParameters.sus11coeffAlpha = { - {-5.23569698615548, -1.45500092391928, 2.7643243644756, -0.0762912296128707, - -0.0201645929971608, 0.0997226845779083, -0.000741669441569556, -0.000485368004931528, - 0.000166230212359982, 0.00103455037278067}, - {-7.7405077383712, 0.892040861541276, 0.39014957203484, -0.00952030929935314, - 0.0185577462685363, 0.000500600568760257, -0.000151227821554572, 0.000245334737283439, - 1.89380065823205e-05, 1.83481122973969e-07}, - {-27.462143709831, -1.68192474287299, 0.689411302961069, -0.0146021086710062, 0.227153492753605, - 0.0815806579791421, 2.92919049429149e-05, 0.00153760357651792, -0.00247865821192621, - -0.00166333309739387}, - {-6.74664748624368, 1.43279156053015, 0.0212787292914553, 0.00764792230365732, - 0.00796410301290615, 0.0014384998868733, -8.95239151813685e-05, 9.55245417090909e-05, - 0.000127251739461239, 3.26943341606363e-05}, - {-2.20391533717674, 1.32902400478083, 0.38633027011889, 0.00104660852197061, - 0.00105228824412283, -0.00242067551428214, -6.98346290136652e-05, -0.000369075232184835, - -1.59510520000704e-05, -0.000448565104826966}, - {-5.29476778147188, 1.4549556336236, 0.561334186252557, -0.00260896342687109, - -0.00855934179001141, -0.0182515354646452, -8.79385828606048e-05, 5.98357681659175e-05, - 0.000146570207542509, 0.000201596912834554}, - {-45.7906613832612, 3.77630104475902, -1.67494598155515, -0.0545433897761635, 0.047897938410221, - -0.0355687158405231, 0.000374738707508583, -0.000448453494537518, 0.000377784972619365, - -0.000276573228333836}, - {-9.11681182090372, 2.06933872940742, 0.26131496122122, -0.0259534033367855, - -0.00777266937872862, -0.00262135395843891, 0.000223790782655445, 6.40488537928934e-05, - 7.75581514100296e-05, -9.25934285039627e-06}, - {183.243883340634, -8.02281039502717, -10.0756951652703, 0.168750521462303, 0.314006821405967, - 0.200264755034566, -0.0011895153717447, -0.00253812476819896, -0.00291324393641628, - -0.00140062522117514}}; - susHandlingParameters.sus11coeffBeta = { - {34.4499366074013, -0.438583698052091, 4.72111001451028, -0.041810050989433, 0.0562461093661426, - 0.0856849892524893, -0.000477813051406167, -3.16404257494464e-05, 0.00102633196865105, - 0.000552974013759876}, - {7.6366298088699, 0.150314752958302, 1.31364679484924, 0.00557696667395871, 0.00163731860604376, - -0.00454759608980269, 5.83979683674572e-05, 4.45944881220665e-05, -4.27874746147066e-05, - -8.77418673597557e-05}, - {130.156215011893, 1.85759000444524, -10.986892391833, -0.00686275191260681, -0.188837138116058, - 0.346177462085361, -0.000183276946352264, -0.000702183496893294, 0.00293145272693857, - -0.00318194442670715}, - {-1.67854820161036, -0.358899332859806, 0.956690839640595, -4.93862910503803e-05, - -0.0136134783014874, -0.00848731301504507, 3.75950499927045e-05, 1.35374694383289e-06, - -0.000156596507890443, -0.000123254220377897}, - {3.67569209537767, -0.387260959713287, 1.31343215605952, -0.00206444615206506, - 0.00145334813110285, -0.00151259497696238, 0.000449492568365603, 6.95883968949488e-07, - 0.000368585523744765, -6.3420715525635e-05}, - {14.3296323024886, -0.182979476956897, 0.306817119309235, -0.00022212115978293, - 0.00463485302909649, 0.0277574953550035, 1.1422454625565e-05, 1.06053257479502e-05, - -2.05720000720608e-05, -0.000338584671430337}, - {-18.7534921817754, 1.14272710923224, 0.460498062012866, -0.00995826989278202, - 0.0658502318647112, 0.00616942819937029, -7.70857153768402e-05, -0.000641755741925561, - 0.00047849204592989, 0.000158509018296766}, - {1.26543621388607, -0.176674379740481, 1.38814920935488, 0.00545485262295305, - -0.00499775616702264, 0.0038057039142173, -6.59604252054511e-05, 6.40211116049053e-05, - -6.74778593434431e-05, -2.81973589469059e-05}, - {116.975421945286, -5.53022680362263, -5.61081660666997, 0.109754904982136, 0.167666815691513, - 0.163137400730063, -0.000609874123906977, -0.00205336098697513, -0.000889232196185857, - -0.00168429567131815}}; - - - rwHandlingParameters.inertiaWheel = 0.000028198; - rwHandlingParameters.maxTrq = 0.0032; //3.2 [mNm] - - //Geometry frame - rwMatrices.alignmentMatrix = { - { 0.9205, 0.0000, -0.9205, 0.0000}, - { 0.0000, -0.9205, 0.0000, 0.9205}, - { 0.3907, 0.3907, 0.3907, 0.3907}}; - - rwMatrices.pseudoInverse = { - { 0.4434, -0.2845, 0.3597}, - { 0.2136, -0.3317, 1.0123}, - { -0.8672, -0.1406, 0.1778}, - { 0.6426, 0.4794, 1.3603}}; - - rwMatrices.nullspace = { -0.7358, 0.5469, -0.3637, -0.1649}; - - kalmanFilterParameters.sensorNoiseSS = 8 * Math::PI / 180; - kalmanFilterParameters.sensorNoiseMAG = 4 * Math::PI / 180; - kalmanFilterParameters.sensorNoiseSTR = 0.1 * Math::PI / 180; - - sunModelParameters.domega = 36000.771; - sunModelParameters.omega_0 = 282.94 * Math::PI / 180.; - sunModelParameters.dm = 35999.049; - sunModelParameters.m_0 = 357.5256; - sunModelParameters.e = 23.4392911 * Math::PI / 180.; - sunModelParameters.e = 0.74508 * Math::PI / 180.; - sunModelParameters.p1 = 6892. / 3600. * Math::PI / 180.; - sunModelParameters.p2 = 72. / 3600. * Math::PI / 180.; - - safeModeControllerParameters.k_rate_mekf = 0.00059437; - safeModeControllerParameters.k_align_mekf = 0.000056875; - - safeModeControllerParameters.sunTargetDir = {1,0,0}; - - detumbleCtrlParameters.gainD = pow(10.0,-3.3); - - // Stuttgart - groundStationParameters.latitudeGs = 48.7495 * Math::PI / 180.; - groundStationParameters.longitudeGs = 9.10384 * Math::PI / 180.; - groundStationParameters.altitudeGs = 500; - - groundStationParameters.earthRadiusEquat = 6378137; - groundStationParameters.earthRadiusPolar = 6356752.314; - -// Geometry frame - targetModeControllerParameters.refDirection = {1,0,0}; - targetModeControllerParameters.refRotRate = {0,0,0}; - targetModeControllerParameters.quatRef = {0,0,0,1}; - - targetModeControllerParameters.avoidBlindStr = true; - targetModeControllerParameters.blindAvoidStart = 1.5; - targetModeControllerParameters.blindAvoidStop = 2.5; - targetModeControllerParameters.blindRotRate = 1 * Math::PI /180; - - targetModeControllerParameters.zeta = 0.3; - targetModeControllerParameters.om = 0.3; - targetModeControllerParameters.qiMin = 0.1; - targetModeControllerParameters.omMax = 1 * Math::PI / 180; - targetModeControllerParameters.gainNullspace = 0.01; - - targetModeControllerParameters.desatMomentumRef = {0,0,0}; - targetModeControllerParameters.deSatGainFactor = 1000; - targetModeControllerParameters.desatOn = true; - - targetModeControllerParameters.omegaEarth = 0.000072921158553; - - strParameters.boresightAxis = { 0.7593, 0,-0.6508}; - strParameters.exclusionAngle = 20 * Math::PI /180; - - magnetorquesParameter.mtq0orientationMatrix = { - { 1, 0, 0}, - { 0, 0, 1}, - { 0,-1, 0}}; - magnetorquesParameter.mtq1orientationMatrix = { - { 1, 0, 0}, - { 0, 1, 0}, - { 0, 0, 1}}; - magnetorquesParameter.mtq2orientationMatrix = { - { 0, 0, 1}, - { 0, 1, 0}, - {-1, 0, 0}}; - magnetorquesParameter.alignmentMatrixMtq = { - { 0, 0,-1}, - {-1, 0, 0}, - { 0, 1, 0}}; - magnetorquesParameter.inverseAlignment = { - { 0,-1, 0}, - { 0, 0, 1}, - {-1, 0, 0}}; - magnetorquesParameter.DipolMax = 0.2; - -} - -AcsParameters::~AcsParameters() { -} +AcsParameters::~AcsParameters() {} /* ReturnValue_t AcsParameters::getParameter(uint8_t domainId, diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 494ddb68..d0d67691 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -6,6 +6,7 @@ #ifndef ACSPARAMETERS_H_ #define ACSPARAMETERS_H_ +#include #include typedef unsigned char uint8_t; @@ -21,60 +22,762 @@ public: const ParameterWrapper *newValues, uint16_t startAtIndex); struct OnBoardParams { - double sampleTime; // [s] + double sampleTime = 0.1; // [s] } onBoardParams; struct InertiaEIVE { - double inertiaMatrix[3][3]; + double inertiaMatrix[3][3] = { + { 1.0, 0.0, 0.0}, + { 0.0, 1.0, 0.0}, + { 0.0, 0.5, 1.0}}; double inertiaMatrixInverse[3][3]; } inertiaEIVE; struct MgmHandlingParameters { - float mgm0orientationMatrix[3][3]; - float mgm1orientationMatrix[3][3]; - float mgm2orientationMatrix[3][3]; - float mgm3orientationMatrix[3][3]; - float mgm4orientationMatrix[3][3]; + float mgm0orientationMatrix[3][3] = { + { 0, 0,-1}, + { 0, 1, 0}, + { 1, 0, 0}}; + float mgm1orientationMatrix[3][3] = { + { 0, 0, 1}, + { 0,-1, 0}, + { 1, 0, 0}}; + float mgm2orientationMatrix[3][3] = { + { 0, 0,-1}, + { 0, 1, 0}, + { 1 ,0, 0}}; + float mgm3orientationMatrix[3][3] = { + { 0, 0, 1}, + { 0,-1, 0}, + { 1, 0, 0}}; + float mgm4orientationMatrix[3][3] = { + { 0, 0,-1}, + {-1, 0, 0}, + { 0, 1, 0}}; } mgmHandlingParameters; struct SusHandlingParameters { - float sus0orientationMatrix[3][3]; - float sus1orientationMatrix[3][3]; - float sus2orientationMatrix[3][3]; - float sus3orientationMatrix[3][3]; - float sus4orientationMatrix[3][3]; - float sus5orientationMatrix[3][3]; - float sus6orientationMatrix[3][3]; - float sus7orientationMatrix[3][3]; - float sus8orientationMatrix[3][3]; - float sus9orientationMatrix[3][3]; - float sus10orientationMatrix[3][3]; - float sus11orientationMatrix[3][3]; + float sus0orientationMatrix[3][3] = { + { 0, 0, 1}, + { 1, 0, 0}, + { 0, 1, 0}}; // FM07 + float sus1orientationMatrix[3][3] = { + { 0, 0,-1}, + {-1, 0, 0}, + { 0, 1, 0}}; // FM06 + float sus2orientationMatrix[3][3] = { + {-1, 0, 0}, + { 0, 0,-1}, + { 0,-1, 0}}; // FM13 + float sus3orientationMatrix[3][3] = { + { 1, 0, 0}, + { 0, 0, 1}, + { 0,-1, 0}}; // FM14 + float sus4orientationMatrix[3][3] = { + { 0,-1, 0}, + { 1, 0, 0}, + { 0, 0, 1}}; // FM05 + float sus5orientationMatrix[3][3] = { + { 1, 0, 0}, + { 0,-1, 0}, + { 0, 0,-1}}; // FM02 + float sus6orientationMatrix[3][3] = { + { 0, 0, 1}, + { 1, 0, 0}, + { 0, 1, 0}}; // FM10 + float sus7orientationMatrix[3][3] = { + { 0, 0,-1}, + {-1, 0, 0}, + { 0, 1, 0}}; // FM01 + float sus8orientationMatrix[3][3] = { + {-1, 0, 0}, + { 0, 0,-1}, + { 0,-1, 0}}; // FM03 + float sus9orientationMatrix[3][3] = { + { 1, 0, 0}, + { 0, 0, 1}, + { 0,-1, 0}}; // FM11 + float sus10orientationMatrix[3][3] = { + { 0,-1, 0}, + { 1, 0, 0}, + { 0, 0, 1}}; // FM09 + float sus11orientationMatrix[3][3] = { + { 1, 0, 0}, + { 0,-1, 0}, + { 0, 0,-1}}; // FM08 - float sus0coeffAlpha[9][10]; // FM07 - float sus0coeffBeta[9][10]; - float sus1coeffAlpha[9][10]; // FM06 - float sus1coeffBeta[9][10]; - float sus2coeffAlpha[9][10]; // FM13 - float sus2coeffBeta[9][10]; - float sus3coeffAlpha[9][10]; // FM14 - float sus3coeffBeta[9][10]; - float sus4coeffAlpha[9][10]; // FM05 - float sus4coeffBeta[9][10]; - float sus5coeffAlpha[9][10]; // FM02 - float sus5coeffBeta[9][10]; - float sus6coeffAlpha[9][10]; // FM10 - float sus6coeffBeta[9][10]; - float sus7coeffAlpha[9][10]; // FM01 - float sus7coeffBeta[9][10]; - float sus8coeffAlpha[9][10]; // FM03 - float sus8coeffBeta[9][10]; - float sus9coeffAlpha[9][10]; // FM11 - float sus9coeffBeta[9][10]; - float sus10coeffAlpha[9][10]; // FM09 - float sus10coeffBeta[9][10]; - float sus11coeffAlpha[9][10]; // FM08 - float sus11coeffBeta[9][10]; + float sus0coeffAlpha[9][10] = { + {10.4400948050067, 1.38202655603079, 0.975299591736672, 0.0172133914423707, -0.0163482459492803, + 0.035730152619911, 0.00021725657060767, -0.000181685375645396, -0.000124096561459262, + 0.00040790566176981}, + {6.38281281805793, 1.81388255990089, 0.28679524291736, 0.0218036823758417, 0.010516766426651, + 0.000446101708841615, 0.00020187044149361, 0.000114957457831415, 1.63114413539632e-05, + -2.0187452317724e-05}, + {-29.3049094555, -0.506844002611835, 1.64911970541112, -0.0336282997119334, 0.053185806861685, + -0.028164943139695, -0.00021098074590512, 0.000643681643489995, -0.000249094601806692, + 0.000231466668650876}, + {-4.76233790255328, 1.1780710601961, -0.194257188545164, 0.00471817228628384, + -0.00183773644319332, -0.00570261621182479, -7.99203367291902e-05, 7.75752247926601e-05, + -9.78534772816957e-06, -4.72083745991256e-05}, + {0.692159025649028, 1.11895461388667, 0.341706834956496, 0.000237989648019541, + -0.000188322779563912, 0.000227310789253953, 0.000133001646828401, -0.000305810826248463, + 0.00010150571088124, -0.000367705461590854}, + {3.38094203317731, 1.24778838596815, 0.067807236112956, -0.00379395536123526, + -0.00339180589343601, -0.00188754615986649, -7.52406312245606e-05, 4.58398750278147e-05, + 6.97244631313601e-05, 2.50519145070895e-05}, + {-7.10546287716029, 0.459472977452686, -1.12251049944014, 0.0175406972371191, + -0.0310525406867782, -0.0531315970690727, -0.000121107664597462, 0.000544665437051928, + -1.78466217018177e-05, -0.00058976234038192}, + {1.60633684055984, 1.1975095485662, 0.180159204664965, -0.00259157601062089, + -0.0038106317634397, 0.000956686555225968, 4.28416721502134e-06, 5.84532336259517e-06, + -2.73407888222758e-05, 5.45131881032866e-06}, + {43.3732235586222, 0.528096786861784, -3.41255850703983, -0.0161629934278675, + 0.0790998053536612, 0.0743822668655928, 0.000237176965460634, -0.000426691336904078, + -0.000889196131314391, -0.000509766491897672}}; + float sus0coeffBeta[9][10] = { + {1.03872648284911, -0.213507239271552, 1.43193059498181, -0.000972717820830235, + -0.00661046096415371, 0.00974284211491888, 2.96098456891215e-05, -8.2933115634257e-05, + -5.52178824394723e-06, 5.73935295303589e-05}, + {3.42242235823356, 0.0848392511283237, 1.24574390342586, 0.00356248195980133, + 0.00100415659893053, -0.00460120247716139, 3.84891005422427e-05, 2.70236417852327e-05, + -7.58501977656551e-05, -8.79809730730992e-05}, + {14.0092526123741, 1.03126714946215, 1.0611008563785, 0.04076462444523, 0.0114106419194518, + 0.00746959159048058, 0.000388033225774727, -0.000124645014888926, -0.000296639947532341, + -0.00020861690864945}, + {1.3562422681189, -0.241585615891602, 1.49170424068611, 0.000179184170448335, + -0.00712399257616284, 0.0121433526723498, 3.29770580642447e-05, 8.78960210966787e-06, + -6.00508568552101e-05, 0.000101583822589461}, + {-0.718855428908583, -0.344067476078684, 1.12397093701762, 0.000236505431484729, + -0.000406441415248947, 0.00032834991502413, 0.000359422093285086, 8.18895560425272e-05, + 0.000316835483508523, 0.000151442890664899}, + {-0.268764016434841, -0.275272048639511, 1.26239753050527, -0.000511224336925231, + 0.0095628568270856, -0.00397960092451418, 1.39587366293607e-05, 1.31409051361129e-05, + -9.83662017231755e-05, 1.87078667116619e-05}, + {27.168106989145, -2.43346872338192, 1.91135512970771, 0.0553180826818016, -0.0481878292619383, + 0.0052773235604729, -0.000428011927975304, 0.000528018208222772, -0.000285438191474895, + -5.71327627917386e-05}, + {-0.169494136517622, -0.350851545482921, 1.19922076033643, 0.0101120903675328, + -0.00151674465424115, 0.00548694086125656, -0.000108240000970513, 1.57202185024105e-05, + -9.77555098179959e-05, 2.09624089449761e-05}, + {-32.3807957489507, 1.8271436443167, 2.51530814328123, -0.0532334586403461, -0.0355980127727253, + -0.0213373892796204, 0.00045506092539885, 0.000545065581027688, 0.000141998709314758, + 0.000101051304611037}}; + float sus1coeffAlpha[9][10] = { + {-27.6783250420482, -0.964805032861791, -0.503974297997131, -0.0446471081874084, + -0.048219538329297, 0.000958491361905381, -0.000290972187162876, -0.000657145721554176, + -0.000178087038629721, 4.09208968678946e-05}, + {2.24803085641869, 1.42938692406645, 0.30104994020693, 0.00756499999397385, 0.0117765927439368, + -0.000743685980641362, 4.69920803836194e-05, 0.000129815636957956, -9.10792250542345e-06, + -2.03870119873411e-05}, + {26.9943033817917, 0.147791175366868, -3.48256070200564, -0.0303332422478656, + 0.0183377266255394, 0.124593616125966, -0.000466003049304431, -0.000272000698791331, + -0.00063621309529853, -0.00158363678978767}, + {-0.221893380318465, 1.29919955307083, 0.21872487901019, 0.0049448219667127, + 0.00291224091529189, 0.00654651987282984, -9.86842469311185e-05, 8.20057454706638e-05, + 6.42331081725944e-05, 7.11656918299053e-05}, + {1.40178843964621, 1.1733111455249, 0.287485528779234, -0.000793970428759834, + 0.000170529273905818, -0.00268807864923086, 9.09553964483881e-05, -0.000271892733575409, + 8.52016306311741e-05, -0.000291797625433646}, + {0.65549617899457, 1.25716478394514, 0.301396415134214, -0.00357289640403958, + -0.000473416364133431, -0.010760332636205, -9.77220176481185e-05, 4.40798040046875e-05, + 2.84958344955681e-05, 0.000128583400693359}, + {6.20958048145025, 1.9528406481596, 1.32915657614139, -0.0326944423378284, -0.0158258335207969, + 0.0328249756354635, 0.00027113042931131, -0.000133980867173428, -0.000357964552318811, + 0.000224235061786191}, + {2.46222812180944, 1.1731834908026, 0.17440330925151, -0.00132279581980401, + -0.00447202005426964, -0.000804321602550913, -1.59526570766446e-05, 2.62946483533391e-05, + 3.28466749016414e-05, -6.63837547601294e-06}, + {42.615758859473, 2.46617281707273, -5.742515881283, -0.131942799763164, 0.20250702826603, + 0.0981562802911027, 0.00189939440077981, -0.0018591621618441, -0.00161121179693977, + -0.00058814458116749}}; + float sus1coeffBeta[9][10] = { + {-12.300032617206, -1.06640894101328, 0.33950802247214, -0.00890867870617722, -0.04872758086642, + -0.0114263851027856, 0.000141061196404012, -0.000675469545483099, -0.000138249928781575, + -0.000138871036200597}, + {10.1631114109768, 0.261654603839785, 1.2376413405181, 0.00888558138614535, 0.00151674939001532, + -0.00534577602313027, 9.19430013005559e-05, 5.39804599087081e-05, -4.15760162347772e-05, + -7.60797902457032e-05}, + {-30.142329062199, 1.26939195100229, 6.14467186367471, 0.0464163689935328, 0.00379001947505376, + -0.165444163648109, 0.000516545385538741, 1.56053219154647e-05, -5.58651971370719e-05, + 0.00173185063955313}, + {12.1454103989862, -0.243589095509132, 2.02543716988677, -0.000857989774598331, + -0.00705278543432513, 0.0250580538307654, 3.50683653081847e-05, -2.63093897408875e-05, + -5.67352645830913e-05, 0.000232270832022029}, + {4.4338108906594, -0.305276965994378, 1.17293558142526, 0.000152618994429577, + 0.00134432642920902, -0.00104036813342885, 0.000334476082056995, 6.74826804343671e-05, + 0.000275311897725414, 7.58157740577916e-05}, + {3.47680700379043, -0.154163381023597, 1.389579838768, 0.000799705880026268, + 0.00401980026462874, -0.00915311817354667, -2.54817301605075e-06, -2.27422984169921e-05, + -2.61224817848938e-05, 6.00381132540332e-05}, + {29.469181543703, -0.722888948550437, 3.3623377135197, 0.00148445490093232, -0.0474780142430845, + 0.0486755575785462, 0.000126295091963757, 0.000526632230895258, -0.000259305985126003, + 0.000412751148048724}, + {2.67029041722834, -0.0837968038501666, 1.37628504937018, 0.00165061312885753, + -0.00953813055064273, 0.0032433005486936, -1.6522452172598e-05, 0.000144574078261271, + -8.47348746872376e-05, -1.92509604512729e-06}, + {-20.959201441285, -2.23605897639125, 5.73044624806043, 0.0354141964763815, 0.0887545371234514, + -0.193862330062381, 0.000216532998121618, -0.00207707610520973, 0.000552928905346826, + 0.00190182163597828}}; + float sus2coeffAlpha[9][10] = { + {6.51602979328333, 0.690575501042577, 1.18185457002269, -0.0153161662266588, + 0.00145972227341484, 0.0351496474730776, -0.000172645571366945, -6.04213053580018e-05, + 9.74494676304114e-05, 0.000334122888261002}, + {0.954398509323963, 1.10996214782069, 0.313314231563221, -0.00367553051112208, + 0.0110290193380194, 0.000240079475656232, -6.93444423181303e-05, 0.000107433381295167, + 1.30750132315838e-05, -2.43580795300515e-05}, + {-55.1159841655056, -1.47449655191106, 3.40106264596874, -0.0621428271456258, + 0.0659788065633613, -0.0791732068323335, -0.000524264070592741, 0.000582093651418709, + -0.000586102213707195, 0.000658133691098817}, + {1.98614148820353, 1.32058724763677, 0.156843003413303, 0.002748082456053, 0.00202677073171519, + 0.00382360695862248, -0.000122364309010211, 5.33354637965168e-05, 3.93641210098335e-05, + 4.06398431916703e-05}, + {3.41223117010734, 1.1597568029329, 0.31881674291653, -0.000382400010917784, + -0.000754945672515052, -0.00079200882313927, 0.000145713118224563, -0.00026910957285589, + 0.000137876961532787, -0.000326798596746712}, + {6.23333031852853, 1.24902998148103, -0.0162317540018123, -0.00338184464699201, + 0.000420329743164687, 0.00202038442335185, -7.10435889754986e-05, -6.04039458988991e-06, + 7.25318569569788e-06, -2.5930447720704e-05}, + {191.759784636909, -10.5228276216193, 8.48306234734519, 0.243240262512846, -0.344226468125615, + 0.126267158197535, -0.00186612281541009, 0.00304415728817747, -0.00304958575196089, + 0.000457236034569107}, + {5.61375025356727, 1.1692295110657, 0.224665256727786, -0.00230481633344849, + -0.00746693012026367, -0.00172583925345173, -7.00823444553058e-06, 7.31362778266959e-05, + 5.81988007269583e-05, 1.3723604109425e-05}, + {98.0250669452855, -2.18500123986039, -6.68238707939385, 0.000754807832106659, + 0.256133336978808, 0.110826583415768, 0.000457663127670018, -0.00197655629847616, + -0.00254305206375073, -0.000466731538082995}}; + float sus2coeffBeta[9][10] = { + {41.1102358678699, 2.3034699186519, 2.74551448799899, 0.061701310929235, 0.0317074142089495, + 0.0308171492962288, 0.00049453042200054, 0.000519222896270701, 2.85420168881716e-05, + 0.000259197384126413}, + {4.46821725251333, 0.0125273331991983, 1.32640678842532, 0.000543566569079156, + 0.00396616601484022, -0.00488408099728387, -3.05734704054868e-06, 7.3424831303621e-05, + -5.49439160235527e-05, -8.30708110469922e-05}, + {64.773396165255, 2.97057686090134, -1.90770757709096, 0.062747116236773, -0.077990648565002, + 0.0613989204238974, 0.00055512113297293, -0.000347045533958329, 0.00104059576098392, + -0.000348638726253297}, + {3.10352939390402, -0.2376108554276, 1.60523925160222, 0.00116454605680723, -0.0067958260462381, + 0.0136561370875238, 2.59929059167486e-05, 3.33825895937897e-05, -5.55828531601728e-05, + 0.000109833374761172}, + {0.156052891975873, -0.320721597024578, 1.15208488414874, 0.00164743688819939, + 0.000534718891498932, 0.000469870758457642, 0.000308432468885207, 0.00011789470679678, + 0.000292373398965513, 0.000183599033441813}, + {2.84967971406268, -0.21374251183113, 1.09938586447269, 2.34894704600407e-05, + 0.00588345375399262, 0.00296966835738407, 8.42707308834155e-06, 2.81870099202641e-06, + -3.56732787246631e-05, -7.04534663356379e-05}, + {-7.59892007483895, 0.358662160515702, 0.805137646978357, 0.00222144376998348, + 0.0464438387809707, 0.00847551828841782, 3.24805702347551e-05, 5.45500807838332e-05, + 0.000941378089367713, 0.000353137737023192}, + {-4.65367165487109, 0.201306010390421, 1.19135575710523, -0.00692801521395975, + 0.00394118754078443, 0.00426360093528599, 6.297683536736e-05, -7.15794236895102e-05, + -7.47076172176468e-05, -1.94516917836346e-05}, + {-59.5882618930651, 3.84530212586425, 3.50497032358686, -0.116100453177197, -0.0380997421813177, + -0.0581898335691109, 0.00111464935006159, 0.000559313074537689, 0.000168067749764069, + 0.000563224178849256}}; + float sus3coeffAlpha[9][10] = { + {-174.687021034355, -7.53454036765748, -9.33798316371397, -0.18212338430986, -0.242523652239734, + -0.202086838965846, -0.00138648793335223, -0.00225430176012882, -0.00198887215340364, + -0.00160678535160774}, + {6.92009692410602, 1.8192037428209, 0.254908171908415, 0.0179273243472017, 0.00894059238779664, + -0.000436952529644, 0.000138070523903458, 9.22759645920339e-05, -9.4312261303588e-06, + -1.76647897892869e-05}, + {-17.9720006944368, 0.230510201259892, 1.10751755772907, -0.00973621304161327, + 0.0554450499198677, -0.00590970792122449, -2.92393772526592e-05, 0.000444329929586969, + -0.000436055839773919, -9.5869891049503e-05}, + {-4.9880829382985, 1.33627775121504, -0.330382157073243, 0.00306744056311184, + 0.00376353074674973, -0.0107453978169225, -0.00010680477021693, 5.17225535432745e-05, + 7.4423443938376e-05, -0.000107927900087035}, + {0.952867982900728, 1.14513280899596, 0.307744203675505, 0.000404669974219378, + -0.000737988606997615, 0.00120218232577844, 0.000191147653645603, -0.000275058867995882, + 0.000137187356620739, -0.000320202731145004}, + {8.076706574364, 1.31338618710295, -0.334634356394277, -0.00209719438033295, + -0.00381753503582303, 0.0100347823323616, -7.00550548221671e-05, -1.97626956996069e-05, + 7.80079707003333e-05, -8.95904360920744e-05}, + {-82.4748312650249, 8.63074484663009, -0.949295700187556, -0.178618807265278, 0.130143669167547, + 0.0284326533865768, 0.00149831261351137, -0.0011583692969717, 0.0010560778729661, + 0.000635404380970666}, + {3.34457857521978, 1.09242517408071, 0.241722402244944, 0.00381629887587041, + -0.00863580122530851, 0.00137050492069702, -8.91046701171713e-05, 8.44169683308007e-05, + -3.54608413548779e-05, 8.54042677832451e-06}, + {78.1540457908649, -1.30266922193303, -5.33605443700115, 0.0184226131926499, 0.146629920899062, + 0.110698519952472, 6.64041537651749e-05, -0.00120174584530713, -0.00133177694921411, + -0.000796422644338886}}; + float sus3coeffBeta[9][10] = { + {-31.5704266802979, -5.10700699133189, 2.84549700473812, -0.122701561048957, -0.11257100034746, + 0.102120576206517, -0.000796645106694696, -0.00192211266325167, -4.99981232866237e-05, + 0.00104036677004523}, + {-0.734294938181273, -0.0694317595592039, 1.34746975389878, -0.00103465544451119, + 0.00389798465946559, -0.00308561832194191, -2.91843250099708e-06, 7.59634622232999e-05, + -6.54571602919161e-05, -0.000104146832644606}, + {24.2649069708536, 3.08145095664586, 1.88975821636026, 0.0767528234206466, -0.0526971951753399, + -0.0477053831942802, 0.000613806533422364, -0.000631628059238499, 0.00026217621127941, + 0.000555307997961608}, + {0.62884078560034, -0.152668817824194, 1.70304497205574, 0.000894387499536142, + -0.00306495168098874, 0.0180087418010658, 1.74990847586174e-05, 3.1263263531046e-05, + -7.1643235604579e-06, 0.000147876621100347}, + {-3.05400297018165, -0.316256447664344, 1.14841722699638, 0.000671621084688467, + -0.000906765726598906, 0.000687041032077189, 0.000323419818039841, 0.000128019308781935, + 0.000286018723737538, 0.000192248693306256}, + {-4.39855066935163, -0.322858945262125, 1.44405016355615, -4.93181749911261e-05, + 0.0127396834052722, -0.00523149676786941, 2.56561922352657e-05, 7.61202764874326e-06, + -0.00014623717850039, 8.12219846932013e-06}, + {110.820397525173, -10.9497307382094, 2.48939759290446, 0.296585618718034, -0.142611297893517, + -0.0141810186612052, -0.00275127095595919, 0.00160686698368569, -0.000872029428758877, + -0.000410522437887563}, + {-7.15740446281205, 0.104233532313688, 1.13155893729292, -0.00350418544400852, + 0.00532058598508803, 0.00459314980222008, 3.09155436939349e-05, -7.60935741692174e-05, + -5.87922606348196e-05, 2.56146268588382e-05}, + {44.8818060495112, -7.94729992210875, 3.59286389225051, 0.217944601088562, 0.108087933176612, + -0.116711715153385, -0.00194260120960441, -0.0015752762498594, -0.000331129410732722, + 0.00125896996438418}}; + float sus4coeffAlpha[9][10] = { + {-12.4581187126738, 0.398038572289047, -0.438887880988151, -0.00965382887938283, + -0.0309322349328842, -0.00359106522420111, -7.79546112299913e-06, -0.000432733997178497, + -9.79031907635314e-05, -1.49299384451257e-05}, + {8.41054378583447, 1.87462327360707, 0.266809999719952, 0.0216455385250676, 0.00879426079919981, + -0.00142295319820553, 0.000194819780653264, 8.57549705064449e-05, -3.56478452552367e-05, + -1.65680920554434e-05}, + {16.4141780945815, 2.57697842088604, 0.373972171754278, 0.0498264199400303, 0.0183175817756131, + -0.008545409848878, 0.000422696533006382, -0.000268245978898508, -0.000663188021815416, + -7.51144017137827e-05}, + {0.796692054977593, 1.26773229735266, 0.247715261673662, 0.00358183885438128, + 0.00216435175662881, 0.00713732829335305, -0.000110129715615857, 3.56051594182427e-05, + 5.03074365340535e-05, 8.40279146176271e-05}, + {2.37491588500165, 1.05997969088519, 0.309540461340971, -0.000405047711742513, + 0.000462224730316111, -0.00201887171945793, 0.000260159805167265, -0.000282867209803598, + 0.000201613303652666, -0.000277796442847579}, + {6.36749007598708, 1.31659760017973, -0.122724934153231, -0.00328808937096891, + -0.00577347207798776, 0.00403172074457999, -7.45676459772001e-05, 1.79838644222274e-05, + 0.000104552066440564, -2.78115121929346e-05}, + {-47.9667098848496, 3.97703197139796, -1.96403894754299, -0.0577989657406978, + 0.0634225576208007, -0.0346023445055141, 0.00045886475369098, -0.000326132951996844, + 0.000716490441845967, -0.000136132038635483}, + {6.21505474256094, 0.871830486201601, 0.286906473833627, 0.007875292606045, + -0.00974634725746389, 0.00128416935792136, -0.000111796743751489, 0.000102016719989187, + -3.3503088289589e-05, -1.03874407813931e-05}, + {102.09801265482, -4.12715152309748, -5.04594403360339, 0.075499959116996, 0.216574192561683, + 0.0750031215784663, -0.000147358932612646, -0.0023710703422108, -0.00143310719642393, + -0.000431914403446768}}; + float sus4coeffBeta[9][10] = { + {-21.5077132684032, -1.60004839699939, -0.0298995033958561, -0.0315563250430659, + -0.0424403625879891, -0.0245426225510417, -0.000209861203016225, -0.000422150973104431, + -0.00030514398458781, -0.000211986731019738}, + {9.07644247897601, 0.207457289788099, 1.26735366597312, 0.00768477352180427, + 0.00429230749575816, -0.00514802326062087, 7.56149591998578e-05, 8.42794730840662e-05, + -3.62215715492783e-05, -5.24384190165239e-05}, + {-33.5225408043693, -3.11167857248829, 1.91760591695775, -0.0963752386435729, + 0.00026620241534153, -0.0256680391021823, -0.00102188712837393, 2.63753563968978e-05, + 0.000113172463974702, 0.000271939918507175}, + {19.1379025029401, -0.225979661987912, 2.72337120022998, -0.00136982412154458, + -0.00447301210555274, 0.046496718064139, 2.09123846958985e-05, -4.30383094864847e-05, + -1.22808643520768e-05, 0.000440555709696048}, + {2.957867714783, -0.316069593806939, 1.06379930645214, 0.00103244713047271, 0.00148059212230411, + 0.000557885068990542, 0.000288633931072557, 0.000172775380291659, 0.000269738457990237, + 0.000254577019084984}, + {2.04155199929521, -0.318303488378033, 1.37820715117028, 0.00114788656817743, + 0.0130051117909245, -0.00743109928493789, 1.22403390396844e-05, -3.19245785131217e-05, + -0.000156735218010879, 3.81458400945988e-05}, + {27.314954181241, -1.43916155634084, 2.48967706992348, 0.0278695408478388, -0.0341141456915131, + 0.0281959785297513, -0.000252996164135396, 0.000163365679366542, -0.000380129463154642, + 0.000159350154429114}, + {-0.274693278266294, 0.0199711721436635, 1.26676843352524, -0.0006713759238817, + -0.00389715205101059, 0.00294298337610857, -9.58643121413979e-06, 6.30700938550725e-05, + -6.07188867796123e-05, 7.72199861279611e-06}, + {-74.1601853968901, 2.55641628908672, 6.38533530714782, -0.0582345132980647, + -0.0653804553172819, -0.138850555683872, 0.000489364157827405, 0.000469559629292745, + 0.000698140692952438, 0.00123017528239406}}; + float sus5coeffAlpha[9][10] = { + {-12.1398741236355, 1.99425442858125, -1.9303044815802, 0.0418421279520049, -0.0309683799946315, + -0.0562201123081437, 0.000522607299552916, -0.000375386573815007, -0.000183899715035788, + -0.000600349486293698}, + {4.51862054729553, 1.72396080253297, 0.274562680698765, 0.0162681383591035, 0.0108410181586673, + -0.000272215427359511, 0.000124164068046579, 0.000125586897851351, -1.24082224214974e-05, + -1.63339067540159e-05}, + {63.0100748193658, 7.78014670478172, 0.327263471268564, 0.181264302704374, -0.0652454854214506, + -0.03906716801285, 0.00166924078925478, -0.000749939315526625, 0.000320696101132374, + 0.000499934751180042}, + {-2.14377722994325, 1.33617641673436, 0.0973465660282871, 0.00389526886867845, + 0.00526064997381395, 0.00244964888333519, -8.59416490903541e-05, 4.58871931007681e-05, + 8.6123353128647e-05, 2.85447259858337e-05}, + {0.164792977301912, 1.17541977248641, 0.348838798760518, -0.000180865118417534, + 0.000331789515553421, -0.000734333865631793, 9.76677859410759e-05, -0.000324347075049525, + 8.66683396011167e-05, -0.000385839566009832}, + {-0.228934187493575, 1.30552820143752, 0.306779576899158, -0.00508763741184706, + -0.00318524263093038, -0.00878095392529144, -6.59040013073836e-05, 8.69122529321691e-05, + 5.73853071731283e-05, 8.56628414466758e-05}, + {22.6047744510684, -0.591739857860868, 0.566728856847393, 0.0498124268150265, + -0.0214126910277926, 0.00538091942017912, -0.000391517685229849, 0.000554321668236216, + 0.000191004410219065, 0.000102775124022018}, + {4.54704081104052, 0.844841244606025, 0.181355971462193, 0.0109743851006749, + -0.00363467884122547, 0.00108873046814694, -0.000153236888951059, 3.14623342713789e-06, + -2.78503202185463e-05, 3.99983788680736e-06}, + {-30.878359404848, 5.20536009886854, -0.674455093700773, -0.10801865891189, -0.0514805639475938, + 0.0503660452068572, 0.00072776817295273, 0.00120288537038655, -0.000301602375634166, + -0.000477098479809266}}; + float sus5coeffBeta[9][10] = { + {16.8155737032787, 0.65475660868259, 1.95532810363711, 0.000295624718662669, 0.0426379914736747, + 0.00192544771588337, -4.94534888281508e-05, 8.32299142575155e-05, 0.000645497238623369, + -0.000234155227840799}, + {9.48268090632318, 0.528942263930744, 1.34030963800712, 0.0173605129814363, 0.00581086655972212, + -0.00365006277801141, 0.000180048140973223, 0.000102002650672644, -4.10833110241736e-05, + -8.7810396165556e-05}, + {-47.8325489165383, -4.78262055949503, 1.66912859871505, -0.143518014673292, 0.0288441527062856, + -0.00322823115861497, -0.00148509910480755, 0.000284265179004289, -0.000175299737313045, + -7.04175618676909e-05}, + {3.70510151312723, -0.272200626024415, 1.5527519845099, 0.000589727630962265, + -0.00889682554869096, 0.0109857452472628, 3.05876215574877e-05, 2.09194236165814e-05, + -8.33769024439277e-05, 6.90991113575066e-05}, + {0.820199776906695, -0.355683467192776, 1.17142130858009, -0.000160174871610729, + 4.09723480153701e-05, 0.000209103751629257, 0.000390331989170637, 6.45642836249667e-05, + 0.000318092703362044, 0.000107158633760141}, + {5.52084497768914, -0.227775345312466, 0.845897282556327, 0.00157426476122436, + 0.00657189797805861, 0.0103797665963117, 2.51479848048895e-05, -4.78371400399983e-05, + -5.20221896473413e-05, -0.000143840492906166}, + {-33.4875689683454, 0.937557276329106, -1.02741065470967, -0.0140023273976314, + 0.0401908729477037, -0.0512457211360142, 7.05537967426573e-05, -0.00027521752411122, + 0.000407657552700476, -0.000458411000693613}, + {0.931346887326171, -0.320804452025793, 1.28866325376154, 0.00912456151698805, + -0.00404367403569981, 0.00477543659981282, -9.43987917474817e-05, 4.66464249533497e-05, + -7.89362487264572e-05, -1.0951496495443e-05}, + {-38.3689359928435, 3.8540516906071, 1.26391725545116, -0.108584643500539, -0.0542697403292778, + 0.0285360568428252, 0.000845084580479371, 0.00114184315411245, -0.000169538153750085, + -0.000336529204350355}}; + float sus6coeffAlpha[9][10] = { + {13.0465222152293, 0.0639132159808454, 2.98083557560227, -0.0773202212713293, + 0.0949075412003712, 0.0503055998355815, -0.00104133434256204, 0.000633099036136146, + 0.00091428505258307, 0.000259857066722932}, + {1.66740227859888, 1.55804368674744, 0.209274741749388, 0.0123798418560859, 0.00724950517167516, + -0.000577445375457582, 8.94374551545955e-05, 6.94513586221567e-05, -1.06065583714065e-05, + -1.43899892666699e-05}, + {8.71610925597519, 1.42112818752419, -0.549859300501301, 0.0374581774684577, 0.0617635595955198, + 0.0447491072679598, 0.00069998577106559, 0.00101018723225412, -4.88501228194031e-06, + -0.000434861113274231}, + {-2.3555601314395, 1.29430213886389, 0.179499593411187, 0.00440896450927253, + 0.00352052300927628, 0.00434187143967281, -9.66615195654703e-05, 3.64923075694275e-05, + 6.09619017310129e-05, 4.23908862836885e-05}, + {-0.858019663974047, 1.10138705956076, 0.278789852526915, -0.000199798507752607, + 0.00112092406838628, -0.00177346866231588, 0.000217816070307086, -0.000240713988238257, + 0.000150795563555828, -0.000279246491927943}, + {7.93661480471297, 1.33902098855997, -0.64010306493848, -0.00307944184518557, + -0.00511421127083497, 0.0204008636376403, -9.50042323904954e-05, 6.01530207062221e-05, + 9.13233708460098e-05, -0.000206717750924323}, + {16.2658124154565, 0.191301571705827, 1.02390350838635, 0.0258487436355216, -0.0219752092833362, + 0.0236916776412211, -0.000350496453661261, -0.000123849795280597, -0.000532190902882765, + 9.36018171121253e-05}, + {-1.53023612303052, 1.29132951637076, 0.181159073530008, -0.0023490608317645, + -0.00370741703297037, -0.000229071300377431, -1.6634455407558e-05, 1.11387154630828e-05, + 1.02609175615251e-05, -9.64717658954667e-06}, + {-32.9918791079688, 0.093536793089853, 4.76858627395571, 0.0595845684553358, -0.054845749101257, + -0.133247382500001, -0.000688999201915199, 7.67286265747961e-05, 0.000868163357631254, + 0.00120099606910313}}; + float sus6coeffBeta[9][10] = { + {12.7380220453847, -0.6087309901836, 2.60957722462363, -0.0415319939920917, 0.0444944768824276, + 0.0223231464060241, -0.000421503508733887, -9.39560038638717e-05, 0.000821479971871302, + -4.5330528329465e-05}, + {1.96846333975847, -0.33921438143463, 1.23957110477613, -0.00948832495296823, + 0.00107211134687287, -0.00410820045700199, -9.33679611473279e-05, 3.72984782145427e-05, + -4.04514487800062e-05, -7.6296149087237e-05}, + {5.7454444934481, -1.58476383793609, -0.418479494289251, -0.0985177320630941, + -0.0862179276808015, 0.0126762052037897, -0.00118207758271301, -0.000190361442918412, + 0.0011723869613426, 0.000122882034141316}, + {2.11042287406433, -0.225942746245056, 1.18084080712528, -0.00103013931607172, + -0.00675606790663387, -0.00106646109062746, 1.7708839355979e-05, -3.13642668374253e-05, + -5.87601932564404e-05, -3.92033314627704e-05}, + {2.96049248725882, -0.286261455028255, 1.09122556181319, -0.000672369023155898, + 0.000574446975796023, 0.000120303729680796, 0.000292285799270644, 0.000170497873487264, + 0.000259925974231328, 0.000222437797823852}, + {1.65218061201483, -0.19535446105784, 1.39609640918411, 0.000961524354787167, + 0.00592400381724333, -0.0078500192096718, -7.02791628080906e-07, -2.07197580883822e-05, + -4.33518182614169e-05, 4.66993119419691e-05}, + {-19.56673237415, 1.06558565338761, 0.151160448373445, -0.0252628659378108, 0.0281230551050938, + -0.0217328869907185, 0.000241309440918385, -0.000116449585258429, 0.000401546410974577, + -0.000147563886502726}, + {1.56167171538684, -0.155299366654736, 1.20084049723279, 0.00457348893890231, + 0.00118888040006052, 0.0029920178735941, -5.583448120596e-05, -2.34496315691865e-05, + -5.3309466243918e-05, 6.20289310356821e-06}, + {1.95050549495182, -2.74909818412705, 3.80268788018641, 0.0629242254381785, 0.0581479035315726, + -0.111361283351269, -0.00047845777495158, -0.00075354297736741, -0.000186887396585446, + 0.00119710704771344}}; + float sus7coeffAlpha[9][10] = { + {-92.1126183408754, -3.77261746189525, -4.50604668349213, -0.0909560776043523, + -0.15646903318971, -0.0766293642415356, -0.00059452135473577, -0.00144790037129283, + -0.00119021101127241, -0.000460110780350978}, + {1.60822506792345, 1.12993931449931, 0.300781032865641, -0.00405149856360946, + 0.0116663280665617, -0.000746071920075153, -8.36092173253351e-05, 0.000126762041147563, + -1.57820750462019e-05, -2.13840141586661e-05}, + {-151.403952985468, -5.77049222793992, 9.71132757422642, -0.113259116970462, 0.284142453949027, + -0.198625061659164, -0.000836450164210354, 0.00174062771509636, -0.00323746390757859, + 0.00124721932086258}, + {3.47391964888809, 1.28788318973591, 0.358380140281919, 0.0033863520864927, 0.00154601909793475, + 0.0103457296050314, -9.56426572270873e-05, 5.48838958555808e-05, 2.97537427220847e-05, + 0.000104735911514185}, + {3.32650947866065, 1.16701012685798, 0.293514063672376, -0.00065850791542434, + -8.61746510464303e-05, -0.00212038990772211, 0.00010377123197, -0.000262818127593837, + 0.000103360882478383, -0.000296739688930329}, + {-0.440176043435378, 1.18923278867097, 0.519516382652818, -0.00138846714677511, + 0.00266491699926247, -0.014254675949624, -4.20279929822439e-05, -5.49260281515447e-05, + -1.00328708454487e-05, 0.000138142092498215}, + {9.54962966738358, 1.83809145920811, 1.82162819067959, -0.0116786627338505, + -0.00496037444422313, 0.0590883547819332, 7.48465315787857e-05, 0.000221693951602584, + 7.96466345174136e-06, 0.000638822537725177}, + {7.04862901290925, 0.876813777672465, 0.16368093989381, 0.00928717461441627, + -0.00276538956293246, 0.00117995419940653, -0.000141511492474493, -6.09796031786385e-06, + -2.62114930414747e-05, -2.88713611443788e-06}, + {135.349147631811, -7.21933296299596, -6.02379024934871, 0.19557354282067, 0.207680233512614, + 0.12880101618361, -0.00169832076532024, -0.00192216719797732, -0.00188763612041332, + -0.00103101801961442}}; + float sus7coeffBeta[9][10] = { + {-12.7115487367622, -1.08890790360556, 0.0579616268854079, -0.0212303293514951, + -0.0395948453851818, -0.0275564242614342, -0.000228652851842222, -0.000148106159109458, + -0.000555136649469199, -0.000198260004582737}, + {-0.988147625946871, -0.759018567468546, 1.20998292002818, -0.0241231836977845, + -0.000572110443300516, -0.00294835038249426, -0.00026533039022186, 6.82250069765274e-06, + 7.21038415209318e-06, -6.54881435118179e-05}, + {98.0979345921564, 4.27381413621355, -4.39956005193548, 0.0709109587666745, -0.172774236139236, + 0.107243391488741, 0.000421832640471043, -0.00140450884710288, 0.00158019019392239, + -0.00078512547169536}, + {4.10892685652543, -0.229301778557857, 1.33380992987117, -0.000250095848720304, + -0.00555205065514645, 0.00355052914398176, 1.62727119770752e-05, -1.26026527654764e-05, + -3.25505031810898e-05, 5.79970895921158e-06}, + {3.09432502337258, -0.300556003790433, 1.17085811008124, 0.00128679594824324, + 0.00148229981422985, 9.15267474159147e-05, 0.000300497843413856, 6.31378865575566e-05, + 0.000258447032558814, 9.79142983264352e-05}, + {8.92336134924575, -0.197306981784312, 0.659908505354084, 0.00175572239373996, + 0.006801023678097, 0.0189775987436792, 9.2187857727721e-06, -4.8706332690626e-05, + -6.887009887486e-05, -0.000266455617735054}, + {-52.0734887320227, 2.64822385560272, -1.72387600304694, -0.0383944891609251, 0.110873671161269, + -0.0475247245070445, 0.000194652401328063, -0.000697307928990137, 0.00124021816001, + -0.000194213899980878}, + {2.08203985879155, -0.127503525368396, 1.17628056094647, 0.00283288065938444, + 0.00394668214608305, 0.00314868636161131, -2.99504350569853e-05, -7.11070816314279e-05, + -6.30148122529749e-05, 2.28114298989664e-05}, + {191.321181158032, -12.2449557187473, -7.21933741885107, 0.267954293388644, 0.331529493933124, + 0.149867703984027, -0.00222279201444128, -0.00284724570619954, -0.00298774060233964, + -0.000988903783752156}}; + float sus8coeffAlpha[9][10] = { + {5.46354311880959, 1.15370126035432, 0.568432485840475, -0.00105094692478431, + -0.000472899673842554, 0.015581320536192, 2.26460844314248e-05, -0.000254397947062058, + 0.000198938007250408, 0.000102026690279006}, + {8.8976133108173, 1.89502416095352, 0.268670471819199, 0.0217013413241972, 0.00973925295182384, + -0.00116357269193765, 0.000185865842232419, 0.000103311614912702, -2.46539447920969e-05, + -2.06292928734686e-05}, + {-45.4550803910752, 1.27220123406993, 5.21483855848504, 0.0315791081623634, 0.0725172355124129, + -0.13947591535243, 0.000412577580637848, 0.000434545096994917, -0.000840043932292312, + 0.00126857487044307}, + {1.81302768546433, 1.20563501267535, 0.344815267182167, 0.00546879453241056, + -0.00115382996865884, 0.010597876132341, -7.75885604486581e-05, 8.99568815949154e-05, + -2.98129544974679e-06, 0.000108913239345604}, + {2.19111439539173, 1.06951675598148, 0.283707798607213, 0.00016478588207518, + 0.000196086067268121, -0.00214980231173703, 0.000237820475654357, -0.000256402967908595, + 0.000165966620658577, -0.000268394081675921}, + {15.0858674915897, 1.27922724811168, -1.0803137812576, -0.00184009775302466, + -0.00458792284209219, 0.0359393555418547, -6.05121024079603e-05, -1.2288384024143e-05, + 8.55484605384438e-05, -0.000379241348638065}, + {-14.9594190080906, 1.79473182195746, -1.00830704063572, 0.000890685410857856, + 0.0408932029176081, -0.0165460857151619, -0.000170544299916973, -0.000370901607010145, + 0.000324089709129097, -9.33010240878062e-05}, + {0.867614491733251, 1.38248194737027, 0.233408537422123, -0.00772942878114575, + -0.00783126068079782, -0.000413713955432221, 4.5775750146291e-05, 6.97323029940275e-05, + 1.70664456940787e-05, 6.75517901233086e-06}, + {2.34474364146174, -0.777275400251477, 2.09531381577911, 0.0170780716714389, 0.102855060371092, + -0.1203441505925, 0.000187004964420911, -0.00141720441050986, -0.000336251285258365, + 0.00145175125888695}}; + float sus8coeffBeta[9][10] = { + {28.3033101237397, 1.77504446792811, 1.70758838986317, 0.0307800697044683, 0.0598759344275936, + -0.014461432284373, 0.000128415617799076, 0.000664419128546701, 0.000312923304130995, + -0.000269026446641855}, + {7.73040563051023, 0.0267291479555493, 1.16189582308493, 0.000611047892976521, + -0.00213680506915073, -0.00517435586596902, -3.60304406049766e-06, -1.74452976404459e-05, + -3.95396925228538e-05, -7.01948519410633e-05}, + {-48.0766126130725, -3.77981206700298, 3.03482861087335, -0.0678496412519532, 0.115260678424016, + -0.0109681510065038, -0.000438011443691466, 0.00097230136258486, -0.000930875177732769, + -0.000203144239955507}, + {12.1881935626341, -0.234345089308583, 2.01134619426134, 0.000181529284001169, + -0.00642848065105061, 0.0243985799415726, 2.0224042581776e-05, 5.22503286757285e-06, + -4.75196303016323e-05, 0.000221160482364556}, + {3.49559433498742, -0.294995112674766, 1.07892379698257, 0.000861664794052587, + 0.00138978933062055, 0.000436385106465176, 0.000288095124755908, 0.000147259769247883, + 0.000256686898599516, 0.000198982412957039}, + {9.36663996178607, -0.171266136751803, 0.799869891484541, -0.000896305696610864, + 0.00477919972789653, 0.0077876110326094, 9.16475263625076e-06, 3.02461250100473e-05, + -3.63917701783264e-05, -0.000101376940843402}, + {9.93372683055145, 1.02056557854246, 3.01635426591734, -0.0477113881140277, -0.0280426434406976, + 0.0438813017696874, 0.000470431190169998, -7.55753674679743e-05, -0.000516444906323815, + 0.000253844418223843}, + {4.12868774589741, -0.305711790187688, 1.15739216407191, 0.00942395115281056, + 0.00264758462357433, 0.00227985850688479, -0.000107537164019682, -4.91396736189963e-05, + -5.3803493814502e-05, 6.80587059728718e-06}, + {64.9193383444005, -1.57724255547465, -3.82166532626293, 0.0104712238987591, 0.0898786950946473, + 0.128910456296131, -8.27123227422217e-05, -0.000143979624107479, -0.00146684876653306, + -0.00102226799570239}}; + float sus9coeffAlpha[9][10] = { + {65.8975109449121, 2.19115342242175, 6.11069527811832, -0.0219884864133703, 0.119985456538482, + 0.142746712551924, -0.000465882328687976, 0.000606525132125852, 0.00141667074621881, + 0.00109715845894006}, + {5.70337356029945, 1.86705636976809, 0.235584190291708, 0.0194937327615426, 0.00973291465247784, + -0.00155675297510773, 0.000147099297988423, 0.000115708967219349, -4.1462310493722e-05, + -9.80097031103588e-06}, + {138.221145997284, 6.07665575619595, -9.08085914250542, 0.0839801072927519, -0.143071750033303, + 0.237868300719915, 0.000626693630444932, -0.000579788170871402, 0.00181740650944343, + -0.00207086879728281}, + {-7.78295582666151, 1.37506685179192, -0.507596181420042, 0.00350118305456038, + 0.00380814310115541, -0.0174012437563343, -0.000124801268056815, 2.96314830184492e-05, + 6.3416992450033e-05, -0.000190177262510221}, + {0.13102597129751, 1.24228303845143, 0.328808873447393, 2.6858679536165e-05, + 0.000231428138164498, -0.000584089095259736, 5.5322167970451e-05, -0.000322205709821716, + 7.71348293209208e-05, -0.000393885990364776}, + {4.64571633968935, 1.2668223691397, -0.158952088650432, -0.0038344859267428, 0.0030051503726095, + 0.00455578826025588, -9.42520993914957e-05, 5.81633314412289e-05, -4.43545804544095e-05, + -4.83524454851519e-05}, + {99.2385930314563, -3.65569343617926, 5.54203926675588, 0.0975630395981933, -0.15701634159692, + 0.107834711298836, -0.000885326636237814, 0.000960753844480462, -0.00179894024848343, + 0.000583066757644971}, + {2.82671549736619, 1.11214198870501, 0.214735318432744, 0.00284415167563662, + -0.00743289575690122, 0.000382705440762292, -7.43232442872501e-05, 6.96994098083348e-05, + -4.15108111710131e-06, 1.33520085213482e-05}, + {36.9013743125415, -0.522392401546163, -1.52452843963663, 0.0261375433218879, 0.060573568610239, + 0.0182582125221054, -0.000244373383911157, -0.000271385147292484, -0.000723799969427732, + 6.76324880239196e-05}}; + float sus9coeffBeta[9][10] = { + {128.70886435409, 7.27355509732751, 7.18142203531244, 0.1536100459329, 0.199455846541636, + 0.101824964939793, 0.00116666116789421, 0.00181595584079788, 0.00159271319494017, + 0.000556768406475719}, + {-7.07933839681024, -0.979062424441878, 1.21792546815617, -0.0295740143783226, + -0.00442780611714201, -0.00329612819203176, -0.000291373125216143, -7.47259350176359e-05, + -4.87265282482212e-05, -7.87490350444332e-05}, + {41.1357193180502, 2.75138456414254, -0.0160889117718198, 0.0274001112562423, + -0.145644717742057, -0.0316076203283094, -0.000136443337244472, -0.00153945199081365, + 0.000938960439977633, 0.000599987111822885}, + {2.7980384746608, -0.234741037383589, 1.5342193016705, -0.000993791566721689, + -0.00787533639513478, 0.00927468655141365, 2.63308697896639e-05, -3.42816267184975e-05, + -8.48879419798771e-05, 3.84043821333798e-05}, + {0.427687530667804, -0.346076633694936, 1.22968527483851, -4.95098138311122e-05, + 0.000298245372198029, 0.000332756250024796, 0.00040375986210644, 5.20675972504572e-05, + 0.000327042170278218, 5.93011568264671e-05}, + {4.50337810133314, -0.279364254817202, 0.945812187846199, 0.000116182663432306, + 0.0115646046622083, 0.00908289960302886, 1.90394667311541e-05, -4.4360223646434e-06, + -0.000131398914898614, -0.000145568992865512}, + {-36.3377213654193, 2.21047221783626, 0.0609982245149821, -0.0670546774988572, + 0.016827777144747, -0.0277834084058314, 0.000778301409125556, 0.000135846745194401, + 0.00043261858797068, -0.00021172728254561}, + {-0.737678205841529, -0.217352122193475, 1.23494846329297, 0.00748173441779792, + 0.0019595873704705, 0.00567253723266176, -8.34768773292938e-05, -3.50608394184873e-05, + -0.000107500091550635, -5.1379722947632e-07}, + {-36.6150844777671, 3.24952006904945, 1.7222457840185, -0.0846362445435584, -0.0625549615377418, + 0.019178365782485, 0.000664877496455304, 0.000942971403881222, 0.000190754698755098, + -0.000372226659190439}}; + float sus10coeffAlpha[9][10] = { + {14.4562393748324, 0.669162330324919, 2.13895255446541, -0.0161997097021299, + 0.00185995785065838, 0.0621351118528379, -0.000278999272493087, 0.000238469666491965, + -0.000279407497782961, 0.000726904943739837}, + {-4.45678285887022, 0.92869611919737, 0.186752102727282, -0.00706160758952316, + 0.00532680276723634, -0.00119102617674229, -0.000105283880098953, 3.90673052334419e-05, + -3.13338277344246e-05, 5.32977236959767e-06}, + {30.4255268053197, 3.00991076401191, -1.4855621363519, 0.033934286288413, -0.0553588742704929, + 0.0299275582316466, 0.000167915322354466, -0.00050925078118232, 0.000463662961330962, + -0.000232919143454163}, + {2.45076465343337, 1.30206564388838, 0.635121046212765, 0.00517109639797675, + 0.00360579544364496, 0.0198490668911362, -9.31556816982662e-05, 6.7313653707875e-05, + 6.4669137025142e-05, 0.000209727581169138}, + {-0.784841314851562, 1.10058314980836, 0.314063830836532, 0.000583003703415889, + 0.000312635453606579, -0.000183738114552387, 0.000214096205760617, -0.000286744686021244, + 0.000159157597180407, -0.00032235099420715}, + {7.19568036510586, 1.33307479701657, -0.465585141952456, -0.0031910726544199, + -0.00546273504371797, 0.0145494754402526, -7.9863949693769e-05, 4.83681329120104e-05, + 8.85844309936609e-05, -0.000143217870916994}, + {-12.8344546267449, 1.36023633150143, -0.728527724854506, 0.019982118403416, 0.0385056413989437, + -0.00468598272326268, -0.000303957957649245, -6.37783846968216e-05, 0.000514049116643205, + 0.000112015427600697}, + {-2.58279031298065, 1.42167821629586, 0.208769467511292, -0.00640190372145885, + -0.0056405289717473, 0.000509611313918708, 2.23310562107823e-05, 3.23685469522147e-05, + -7.55982776243849e-06, 2.78417756661088e-06}, + {-29.7178996143914, 2.636972251183, 1.97316329325243, -0.03983524158327, -0.0193152048730234, + -0.0600902798379509, 0.00031786916010672, 0.000162178988605602, 0.000224550786416246, + 0.000614337977361927}}; + float sus10coeffBeta[9][10] = { + {12.4771349792459, 1.44317849705414, 0.975637226331561, 0.0430284146301043, 0.0220810531548995, + -0.0220926906772, 0.000310052324529521, 0.000658151808869523, -0.000288026365111098, + -0.000214619731807045}, + {-0.113203260140131, -0.272424061092191, 1.27704377191184, -0.00791746619331075, + 0.00278646694862191, -0.00398881099259934, -8.09569694307212e-05, 5.99617384829016e-05, + -5.4550919751855e-05, -8.6314530565085e-05}, + {-48.585664295448, -2.04899787231903, 4.48757129623549, -0.0226180460431321, 0.090326735447661, + -0.0722998813632622, -6.77623771415477e-05, 0.000562585419036509, -0.000956171370931993, + 0.000491554402311223}, + {-1.20986884955482, -0.215604107185474, 1.22123198786617, 0.000256508527822089, + -0.00625056735692847, 0.00262961582224303, 2.27433984698861e-05, 1.60471509861372e-05, + -4.85061736834262e-05, -1.8387092782907e-06}, + {-0.250205907903409, -0.315819331560782, 1.09018364376391, -0.000521787614293089, + -0.000500747760913489, 2.48184307342838e-05, 0.000313799238640988, 0.000136669146368744, + 0.000278914324565192, 0.000218512838469476}, + {-1.38512578184076, -0.240456589364121, 1.34170304231345, 0.00017499230372669, + 0.0070862275911073, -0.00460640844814105, 1.27594111036696e-05, -4.73855624902052e-06, + -5.41141037812903e-05, 8.50767021818388e-06}, + {58.9917559342216, -2.28705697628345, 5.35995190407842, 0.0214721399750612, -0.112195722921667, + 0.0890150265857542, -0.000100675657768708, 0.000493488022135339, -0.00137672908303878, + 0.000518683157694955}, + {3.18905073365834, -0.633376549706314, 1.17190259811174, 0.0188817945597344, + 0.00107470708915782, 0.00400880471375267, -0.000197312295539118, -2.46543035998379e-05, + -6.07871064300252e-05, 1.91822310311955e-05}, + {-21.6881499304099, -0.563186103920008, 3.70747028664292, 0.021112883967427, + -0.00650020689049325, -0.0778533644688476, -0.000131921888670268, -0.000402754836445439, + 0.000551249824375055, 0.00062236627391337}}; + float sus11coeffAlpha[9][10] = { + {-5.23569698615548, -1.45500092391928, 2.7643243644756, -0.0762912296128707, + -0.0201645929971608, 0.0997226845779083, -0.000741669441569556, -0.000485368004931528, + 0.000166230212359982, 0.00103455037278067}, + {-7.7405077383712, 0.892040861541276, 0.39014957203484, -0.00952030929935314, + 0.0185577462685363, 0.000500600568760257, -0.000151227821554572, 0.000245334737283439, + 1.89380065823205e-05, 1.83481122973969e-07}, + {-27.462143709831, -1.68192474287299, 0.689411302961069, -0.0146021086710062, 0.227153492753605, + 0.0815806579791421, 2.92919049429149e-05, 0.00153760357651792, -0.00247865821192621, + -0.00166333309739387}, + {-6.74664748624368, 1.43279156053015, 0.0212787292914553, 0.00764792230365732, + 0.00796410301290615, 0.0014384998868733, -8.95239151813685e-05, 9.55245417090909e-05, + 0.000127251739461239, 3.26943341606363e-05}, + {-2.20391533717674, 1.32902400478083, 0.38633027011889, 0.00104660852197061, + 0.00105228824412283, -0.00242067551428214, -6.98346290136652e-05, -0.000369075232184835, + -1.59510520000704e-05, -0.000448565104826966}, + {-5.29476778147188, 1.4549556336236, 0.561334186252557, -0.00260896342687109, + -0.00855934179001141, -0.0182515354646452, -8.79385828606048e-05, 5.98357681659175e-05, + 0.000146570207542509, 0.000201596912834554}, + {-45.7906613832612, 3.77630104475902, -1.67494598155515, -0.0545433897761635, 0.047897938410221, + -0.0355687158405231, 0.000374738707508583, -0.000448453494537518, 0.000377784972619365, + -0.000276573228333836}, + {-9.11681182090372, 2.06933872940742, 0.26131496122122, -0.0259534033367855, + -0.00777266937872862, -0.00262135395843891, 0.000223790782655445, 6.40488537928934e-05, + 7.75581514100296e-05, -9.25934285039627e-06}, + {183.243883340634, -8.02281039502717, -10.0756951652703, 0.168750521462303, 0.314006821405967, + 0.200264755034566, -0.0011895153717447, -0.00253812476819896, -0.00291324393641628, + -0.00140062522117514}}; + float sus11coeffBeta[9][10] = { + {34.4499366074013, -0.438583698052091, 4.72111001451028, -0.041810050989433, 0.0562461093661426, + 0.0856849892524893, -0.000477813051406167, -3.16404257494464e-05, 0.00102633196865105, + 0.000552974013759876}, + {7.6366298088699, 0.150314752958302, 1.31364679484924, 0.00557696667395871, 0.00163731860604376, + -0.00454759608980269, 5.83979683674572e-05, 4.45944881220665e-05, -4.27874746147066e-05, + -8.77418673597557e-05}, + {130.156215011893, 1.85759000444524, -10.986892391833, -0.00686275191260681, -0.188837138116058, + 0.346177462085361, -0.000183276946352264, -0.000702183496893294, 0.00293145272693857, + -0.00318194442670715}, + {-1.67854820161036, -0.358899332859806, 0.956690839640595, -4.93862910503803e-05, + -0.0136134783014874, -0.00848731301504507, 3.75950499927045e-05, 1.35374694383289e-06, + -0.000156596507890443, -0.000123254220377897}, + {3.67569209537767, -0.387260959713287, 1.31343215605952, -0.00206444615206506, + 0.00145334813110285, -0.00151259497696238, 0.000449492568365603, 6.95883968949488e-07, + 0.000368585523744765, -6.3420715525635e-05}, + {14.3296323024886, -0.182979476956897, 0.306817119309235, -0.00022212115978293, + 0.00463485302909649, 0.0277574953550035, 1.1422454625565e-05, 1.06053257479502e-05, + -2.05720000720608e-05, -0.000338584671430337}, + {-18.7534921817754, 1.14272710923224, 0.460498062012866, -0.00995826989278202, + 0.0658502318647112, 0.00616942819937029, -7.70857153768402e-05, -0.000641755741925561, + 0.00047849204592989, 0.000158509018296766}, + {1.26543621388607, -0.176674379740481, 1.38814920935488, 0.00545485262295305, + -0.00499775616702264, 0.0038057039142173, -6.59604252054511e-05, 6.40211116049053e-05, + -6.74778593434431e-05, -2.81973589469059e-05}, + {116.975421945286, -5.53022680362263, -5.61081660666997, 0.109754904982136, 0.167666815691513, + 0.163137400730063, -0.000609874123906977, -0.00205336098697513, -0.000889232196185857, + -0.00168429567131815}}; float filterAlpha; float sunThresh; @@ -91,101 +794,110 @@ public: double rw1orientationMatrix[3][3]; double rw2orientationMatrix[3][3]; double rw3orientationMatrix[3][3]; - double inertiaWheel; - double maxTrq; + double inertiaWheel = 0.000028198; + double maxTrq = 0.0032; //3.2 [mNm] } rwHandlingParameters; + struct RwMatrices { + double alignmentMatrix[3][4] = { + { 0.9205, 0.0000, -0.9205, 0.0000}, + { 0.0000, -0.9205, 0.0000, 0.9205}, + { 0.3907, 0.3907, 0.3907, 0.3907}}; + double pseudoInverse[4][3] = { + { 0.4434, -0.2845, 0.3597}, + { 0.2136, -0.3317, 1.0123}, + { -0.8672, -0.1406, 0.1778}, + { 0.6426, 0.4794, 1.3603}}; + double without0[4][3]; + double without1[4][3]; + double without2[4][3]; + double without3[4][3]; + double nullspace[4] = { -0.7358, 0.5469, -0.3637, -0.1649}; + } rwMatrices; + struct SafeModeControllerParameters { - double k_rate_mekf; - double k_align_mekf; + double k_rate_mekf = 0.00059437; + double k_align_mekf = 0.000056875; double k_rate_no_mekf; double k_align_no_mekf; double sunMagAngleMin; - double sunTargetDir[3]; //Body frame + double sunTargetDir[3] = { 1, 0, 0}; //Body frame double satRateRef[3]; //Body frame } safeModeControllerParameters; struct DetumbleCtrlParameters { - double gainD; + double gainD = pow(10.0,-3.3); } detumbleCtrlParameters; - + // ToDo: mutiple structs for different pointing mode controllers? struct PointingModeControllerParameters { double updtFlag; double A_rw[3][12]; - double refDirection[3]; - double refRotRate[3]; - double quatRef[4]; - bool avoidBlindStr; - double blindAvoidStart; - double blindAvoidStop; - double blindRotRate; + double refDirection[3] = { 1, 0, 0}; + double refRotRate[3] = { 0, 0, 0}; + double quatRef[4] = { 0, 0, 0, 1}; + bool avoidBlindStr = true; + double blindAvoidStart = 1.5; + double blindAvoidStop = 2.5; + double blindRotRate = 1 * Math::PI /180; - double zeta; + double zeta = 0.3; double zetaLow; - double om; + double om = 0.3; double omLow; - double qiMin; - double omMax; - double gainNullspace; + double omMax = 1 * Math::PI / 180; + double qiMin = 0.1; + double gainNullspace = 0.01; - double desatMomentumRef[3]; - double deSatGainFactor; - bool desatOn; + double desatMomentumRef[3] = {0,0,0}; + double deSatGainFactor = 1000; + bool desatOn = true; - double omegaEarth; + double omegaEarth = 0.000072921158553; } inertialModeControllerParameters, nadirModeControllerParameters, targetModeControllerParameters; - struct RWMatrices { - double alignmentMatrix[3][4]; - double pseudoInverse[4][3]; - double without0[4][3]; - double without1[4][3]; - double without2[4][3]; - double without3[4][3]; - double nullspace[4]; - } rwMatrices; - struct StrParameters { - double exclusionAngle; + double exclusionAngle = 20 * Math::PI /180; // double strOrientationMatrix[3][3]; - double boresightAxis[3]; //in body/geometry frame + double boresightAxis[3] = { 0.7593, 0.0000,-0.6508}; //in body/geometry frame } strParameters; struct GpsParameters { } gpsParameters; struct GroundStationParameters { - double latitudeGs; // [rad] Latitude - double longitudeGs; // [rad] Longitude - double altitudeGs; // [m] Altitude - double earthRadiusEquat; // [m] - double earthRadiusPolar; // [m] - } groundStationParameters; + double latitudeGs = 48.7495 * Math::PI / 180.; // [rad] Latitude + double longitudeGs = 9.10384 * Math::PI / 180.; // [rad] Longitude + double altitudeGs = 500; // [m] Altitude + double earthRadiusEquat = 6378137; // [m] + double earthRadiusPolar = 6356752.314; // [m] + } groundStationParameters; // Stuttgart struct SunModelParameters { enum UseSunModel { NO = 0, YES = 3 }; uint8_t useSunModel; - float domega; - float omega_0; //Rektaszension des Aufsteigenden Knotens plus Argument des Perigäums - float m_0; //coefficients for mean anomaly - float dm; //coefficients for mean anomaly - float e; //angle of earth's rotation axis - float e1; - float p1; //some parameter - float p2; //some parameter + float domega = 36000.771; + float omega_0 = 282.94 * Math::PI / 180.; //RAAN plus argument of perigee + float m_0 = 357.5256; //coefficients for mean anomaly + float dm = 35999.049; //coefficients for mean anomaly + // ToDo: check correct assignment of e and e1. Both were assigned to e before + float e = 23.4392911 * Math::PI / 180.; //angle of earth's rotation axis + float e1 = 0.74508 * Math::PI / 180.; + // + float p1 = 6892. / 3600. * Math::PI / 180.; //some parameter + float p2 = 72. / 3600. * Math::PI / 180.; //some parameter } sunModelParameters; struct KalmanFilterParameters { @@ -195,9 +907,9 @@ public: double processNoiseOmega[3]; double processNoiseQuaternion[4]; - double sensorNoiseSTR; - double sensorNoiseSS; - double sensorNoiseMAG; + double sensorNoiseSTR = 0.1 * Math::PI / 180; + double sensorNoiseSS = 8 * Math::PI / 180; + double sensorNoiseMAG = 4 * Math::PI / 180; double sensorNoiseRMU[3]; double sensorNoiseArwRmu; //Angular Random Walk @@ -206,12 +918,27 @@ public: struct MagnetorquesParameter { - double mtq0orientationMatrix[3][3]; - double mtq1orientationMatrix[3][3]; - double mtq2orientationMatrix[3][3]; - double alignmentMatrixMtq[3][3]; - double inverseAlignment[3][3]; - double DipolMax; // [Am^2] + 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] } magnetorquesParameter; -- 2.34.1 From 5f17f365e3458d5d7ccb23eb22fe8fcc3ba1c668 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 27 Sep 2022 11:06:11 +0200 Subject: [PATCH 031/101] fixed local includes --- mission/controller/acs/ActuatorCmd.cpp | 6 +- mission/controller/acs/ActuatorCmd.h | 10 +- mission/controller/acs/Guidance.cpp | 10 +- mission/controller/acs/Guidance.h | 6 +- mission/controller/acs/Igrf13Model.cpp | 10 +- mission/controller/acs/Igrf13Model.h | 2 +- .../acs/MultiplicativeKalmanFilter.cpp | 12 +- .../acs/MultiplicativeKalmanFilter.h | 2 +- mission/controller/acs/Navigation.cpp | 11 +- mission/controller/acs/Navigation.h | 10 +- mission/controller/acs/OutputValues.cpp | 2 +- mission/controller/acs/SensorProcessing.cpp | 6 +- mission/controller/acs/SensorProcessing.h | 11 +- mission/controller/acs/SensorValues.cpp | 5 +- mission/controller/acs/SusConverter.cpp | 263 +++++++++--------- mission/controller/acs/SusConverter.h | 39 ++- mission/controller/acs/control/Detumble.cpp | 6 +- mission/controller/acs/control/Detumble.h | 11 +- mission/controller/acs/control/PtgCtrl.cpp | 12 +- mission/controller/acs/control/PtgCtrl.h | 10 +- mission/controller/acs/control/SafeCtrl.cpp | 11 +- mission/controller/acs/control/SafeCtrl.h | 11 +- 22 files changed, 235 insertions(+), 231 deletions(-) diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index 3b4ed71e..261277a0 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -6,14 +6,14 @@ */ -#include +#include "ActuatorCmd.h" +#include "util/MathOperations.h" +#include "util/CholeskyDecomposition.h" #include -#include #include #include #include #include -#include ActuatorCmd::ActuatorCmd(AcsParameters *acsParameters_) { acsParameters = *acsParameters_; diff --git a/mission/controller/acs/ActuatorCmd.h b/mission/controller/acs/ActuatorCmd.h index 85ef1532..820f1f00 100644 --- a/mission/controller/acs/ActuatorCmd.h +++ b/mission/controller/acs/ActuatorCmd.h @@ -9,11 +9,11 @@ #define ACTUATORCMD_H_ -#include -#include -#include -#include -#include +#include "AcsParameters.h" +#include "SensorProcessing.h" +#include "MultiplicativeKalmanFilter.h" +#include "SensorValues.h" +#include "OutputValues.h" class ActuatorCmd{ public: diff --git a/mission/controller/acs/Guidance.cpp b/mission/controller/acs/Guidance.cpp index 158ee9f0..a6a91a81 100644 --- a/mission/controller/acs/Guidance.cpp +++ b/mission/controller/acs/Guidance.cpp @@ -8,12 +8,12 @@ #include "Guidance.h" #include "string.h" +#include "util/MathOperations.h" +#include "util/CholeskyDecomposition.h" #include -#include -#include -#include -#include -#include +#include +#include +#include Guidance::Guidance(AcsParameters *acsParameters_) { acsParameters = *acsParameters_; diff --git a/mission/controller/acs/Guidance.h b/mission/controller/acs/Guidance.h index 736d8b9b..bf53d767 100644 --- a/mission/controller/acs/Guidance.h +++ b/mission/controller/acs/Guidance.h @@ -9,9 +9,9 @@ #define GUIDANCE_H_ -#include -#include -#include +#include "AcsParameters.h" +#include "SensorValues.h" +#include "OutputValues.h" #include diff --git a/mission/controller/acs/Igrf13Model.cpp b/mission/controller/acs/Igrf13Model.cpp index 91bfad15..75d3c9a1 100644 --- a/mission/controller/acs/Igrf13Model.cpp +++ b/mission/controller/acs/Igrf13Model.cpp @@ -6,15 +6,15 @@ */ #include "Igrf13Model.h" +#include "util/MathOperations.h" #include #include #include //#include -#include -#include -#include -#include -#include +#include +#include +#include +#include Igrf13Model::Igrf13Model(){ diff --git a/mission/controller/acs/Igrf13Model.h b/mission/controller/acs/Igrf13Model.h index 3ea2cb40..d89865ca 100644 --- a/mission/controller/acs/Igrf13Model.h +++ b/mission/controller/acs/Igrf13Model.h @@ -16,11 +16,11 @@ #ifndef IGRF13MODEL_H_ #define IGRF13MODEL_H_ -#include #include #include #include #include +#include // Output should be transformed to [T] instead of [nT] diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.cpp b/mission/controller/acs/MultiplicativeKalmanFilter.cpp index b2c8a963..5f7facd2 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.cpp +++ b/mission/controller/acs/MultiplicativeKalmanFilter.cpp @@ -5,14 +5,14 @@ * Author: rooob */ +#include "MultiplicativeKalmanFilter.h" +#include "util/CholeskyDecomposition.h" +#include "util/MathOperations.h" #include #include -#include -#include -#include -#include "MultiplicativeKalmanFilter.h" -#include -#include +#include +#include +#include /*Initialisation of values for parameters in constructor*/ MultiplicativeKalmanFilter::MultiplicativeKalmanFilter(AcsParameters *acsParameters_) : diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.h b/mission/controller/acs/MultiplicativeKalmanFilter.h index f972ab5a..542db996 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.h +++ b/mission/controller/acs/MultiplicativeKalmanFilter.h @@ -14,9 +14,9 @@ #ifndef MULTIPLICATIVEKALMANFILTER_H_ #define MULTIPLICATIVEKALMANFILTER_H_ +#include "config/classIds.h" #include //uint8_t #include /*purpose, timeval ?*/ -#include "acs/config/classIds.h" //#include <_timeval.h> #include "AcsParameters.h" diff --git a/mission/controller/acs/Navigation.cpp b/mission/controller/acs/Navigation.cpp index 2cb70389..a2e3aa5d 100644 --- a/mission/controller/acs/Navigation.cpp +++ b/mission/controller/acs/Navigation.cpp @@ -6,12 +6,13 @@ */ #include "Navigation.h" +#include "util/MathOperations.h" +#include "util/CholeskyDecomposition.h" #include -#include -#include -#include -#include -#include +#include +#include +#include + Navigation::Navigation(AcsParameters *acsParameters_): multiplicativeKalmanFilter(acsParameters_){ acsParameters = *acsParameters_; diff --git a/mission/controller/acs/Navigation.h b/mission/controller/acs/Navigation.h index 75bbade5..6691b8aa 100644 --- a/mission/controller/acs/Navigation.h +++ b/mission/controller/acs/Navigation.h @@ -9,11 +9,11 @@ #define NAVIGATION_H_ -#include -#include -#include -#include -#include +#include "AcsParameters.h" +#include "SensorProcessing.h" +#include "MultiplicativeKalmanFilter.h" +#include "SensorValues.h" +#include "OutputValues.h" class Navigation{ public: diff --git a/mission/controller/acs/OutputValues.cpp b/mission/controller/acs/OutputValues.cpp index 3deb4043..d035f621 100644 --- a/mission/controller/acs/OutputValues.cpp +++ b/mission/controller/acs/OutputValues.cpp @@ -4,7 +4,7 @@ * Created on: 30 Mar 2022 * Author: rooob */ -#include +#include "OutputValues.h" namespace ACS { diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index 7b89daf1..61f8092b 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -6,14 +6,14 @@ */ #include "SensorProcessing.h" +#include "Igrf13Model.h" +#include "util/MathOperations.h" +#include #include #include #include #include #include -#include -#include -#include using namespace Math; // Thought: Maybe separate file for transforming of sensor values diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h index 23abcc40..aa4dc3bd 100644 --- a/mission/controller/acs/SensorProcessing.h +++ b/mission/controller/acs/SensorProcessing.h @@ -5,13 +5,14 @@ #ifndef SENSORPROCESSING_H_ #define SENSORPROCESSING_H_ +#include "AcsParameters.h" +#include "SensorValues.h" +#include "OutputValues.h" +#include "config/classIds.h" #include //uint8_t #include /*purpose, timeval ?*/ -#include -#include -#include -#include -#include +#include + /*Planned: * - Fusion of Sensor Measurements - diff --git a/mission/controller/acs/SensorValues.cpp b/mission/controller/acs/SensorValues.cpp index 414c93ef..11720aeb 100644 --- a/mission/controller/acs/SensorValues.cpp +++ b/mission/controller/acs/SensorValues.cpp @@ -4,11 +4,10 @@ * Created on: 30 Mar 2022 * Author: rooob */ -#include - +#include "SensorValues.h" #include #include -#include +#include namespace ACS { diff --git a/mission/controller/acs/SusConverter.cpp b/mission/controller/acs/SusConverter.cpp index 151648ed..c2d65133 100644 --- a/mission/controller/acs/SusConverter.cpp +++ b/mission/controller/acs/SusConverter.cpp @@ -5,13 +5,15 @@ * Author: Timon Schwarz */ +#include "SusConverter.h" #include //for atan2 #include -#include #include +#include +#include void SunSensor::setSunSensorData() { - // Creates dummy sensordata, replace with SUS devicehandler / channel readout + // ToDo: exchange dummy values with DataPool susChannelValues[0] = {3913, 3912, 3799, 4056}; susChannelValues[1] = {3913, 3912, 3799, 4056}; susChannelValues[2] = {3913, 3912, 3799, 4056}; @@ -26,71 +28,73 @@ void SunSensor::setSunSensorData() { susChannelValues[11] = {3913, 3912, 3799, 4056}; } -void SunSensor::checkSunSensorData(uint8_t Sensornumber) { - uint16_t ChannelValueSum; +void SunSensor::checkSunSensorData(uint8_t susNumber) { + uint16_t channelValueSum; // Check individual channel values for (int k = 0; k < 4; k++) { // iteration above all photodiode quarters - if (susChannelValues[Sensornumber][k] <= ChannelValueCheckLow || - susChannelValues[Sensornumber][k] > ChannelValueCheckHigh) { // Channel values out of range for 12 bit SUS + if (susChannelValues[susNumber][k] <= channelValueCheckLow || + susChannelValues[susNumber][k] > channelValueCheckHigh) { // Channel values out of range for 12 bit SUS // channel measurement range? - ValidityNumber[Sensornumber] = false; // false --> Data not valid + validFlag[susNumber] = returnvalue::FAILED; /*printf( "The value of channel %i from sun sensor %i is not inside the borders of valid data with " "a value of %i \n", - k, Sensornumber, ChannelValue[k]);*/ - } else if (susChannelValues[Sensornumber][k] > - susChannelValues[Sensornumber][4]) { // Channel values higher than zero current threshold GNDREF? - ValidityNumber[Sensornumber] = false; + k, susNumber, ChannelValue[k]);*/ + } else if (susChannelValues[susNumber][k] > + susChannelValues[susNumber][4]) { // Channel values higher than zero current threshold GNDREF? + validFlag[susNumber] = returnvalue::FAILED; /*printf( "The value of channel %i from sun sensor %i is higher than the zero current threshold " "GNDREF\n", - k, Sensornumber);*/ + k, susNumber);*/ }; }; // check sum of all channel values to check if sun sensor is illuminated by the sun (sum is // smaller than a treshold --> sun sensor is not illuminated by the sun, but by the moon // reflection or earth albedo) - ChannelValueSum = - 4 * susChannelValues[Sensornumber][4] - (susChannelValues[Sensornumber][0] + - susChannelValues[Sensornumber][1] + susChannelValues[Sensornumber][2] + - susChannelValues[Sensornumber][3]); - if ((ChannelValueSum < ChannelValueSumHigh) && (ChannelValueSum > ChannelValueSumLow)) { - ValidityNumber[Sensornumber] = false; - //printf("Sun sensor %i is not illuminated by the sun\n", Sensornumber); + channelValueSum = + 4 * susChannelValues[susNumber][4] - (susChannelValues[susNumber][0] + + susChannelValues[susNumber][1] + susChannelValues[susNumber][2] + + susChannelValues[susNumber][3]); + if ((channelValueSum < channelValueSumHigh) && (channelValueSum > channelValueSumLow)) { + validFlag[susNumber] = returnvalue::FAILED; + //printf("Sun sensor %i is not illuminated by the sun\n", susNumber); }; } -void SunSensor::AngleCalculation(uint8_t Sensornumber) { - float xout, yout, s = 0.03; // s=[mm] - uint8_t d = 5, h = 1; // d=[mm] h=[mm] +void SunSensor::calcAngle(uint8_t susNumber) { + float xout, yout; + float s = 0.03; // s=[mm] gap between diodes + uint8_t d = 5; // d=[mm] edge length of the quadratic aperture + uint8_t h = 1; // h=[mm] distance between diodes and aperture int ch0, ch1, ch2, ch3; // Substract measurement values from GNDREF zero current threshold - ch0 = susChannelValues[Sensornumber][4] - susChannelValues[Sensornumber][0]; - ch1 = susChannelValues[Sensornumber][4] - susChannelValues[Sensornumber][1]; - ch2 = susChannelValues[Sensornumber][4] - susChannelValues[Sensornumber][2]; - ch3 = susChannelValues[Sensornumber][4] - susChannelValues[Sensornumber][3]; + ch0 = susChannelValues[susNumber][4] - susChannelValues[susNumber][0]; + ch1 = susChannelValues[susNumber][4] - susChannelValues[susNumber][1]; + ch2 = susChannelValues[susNumber][4] - susChannelValues[susNumber][2]; + ch3 = susChannelValues[susNumber][4] - susChannelValues[susNumber][3]; // Calculation of x and y xout = ((d - s) / 2) * (ch2 - ch3 - ch0 + ch1) / (ch0 + ch1 + ch2 + ch3); //[mm] yout = ((d - s) / 2) * (ch2 + ch3 - ch0 - ch1) / (ch0 + ch1 + ch2 + ch3); //[mm] // Calculation of the angles - AlphaBetaRaw[Sensornumber][0] = atan2(xout, h) * (180 / M_PI); //[°] - AlphaBetaRaw[Sensornumber][1] = atan2(yout, h) * (180 / M_PI); //[°] + alphaBetaRaw[susNumber][0] = atan2(xout, h) * (180 / M_PI); //[°] + alphaBetaRaw[susNumber][1] = atan2(yout, h) * (180 / M_PI); //[°] } -void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { - switch (Sensornumber) { // search for the correct calibration coefficients for each SUS +void SunSensor::setCalibrationCoefficients(uint8_t susNumber) { + switch (susNumber) { // search for the correct calibration coefficients for each SUS case 0: for (uint8_t row = 0; row < 9; row++) { // save the correct coefficients in the right SUS class for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus0coeffAlpha[row][column]; - CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus0coeffBeta[row][column]; + coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus0coeffAlpha[row][column]; + coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus0coeffBeta[row][column]; } } break; @@ -98,8 +102,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 1: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus1coeffAlpha[row][column]; - CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus1coeffBeta[row][column]; + coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus1coeffAlpha[row][column]; + coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus1coeffBeta[row][column]; } } break; @@ -107,8 +111,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 2: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus2coeffAlpha[row][column]; - CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus2coeffBeta[row][column]; + coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus2coeffAlpha[row][column]; + coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus2coeffBeta[row][column]; } } break; @@ -116,8 +120,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 3: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus3coeffAlpha[row][column]; - CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus3coeffBeta[row][column]; + coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus3coeffAlpha[row][column]; + coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus3coeffBeta[row][column]; } } break; @@ -125,8 +129,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 4: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus4coeffAlpha[row][column]; - CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus4coeffBeta[row][column]; + coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus4coeffAlpha[row][column]; + coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus4coeffBeta[row][column]; } } break; @@ -134,8 +138,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 5: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus5coeffAlpha[row][column]; - CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus5coeffBeta[row][column]; + coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus5coeffAlpha[row][column]; + coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus5coeffBeta[row][column]; } } break; @@ -143,8 +147,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 6: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus6coeffAlpha[row][column]; - CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus6coeffBeta[row][column]; + coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus6coeffAlpha[row][column]; + coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus6coeffBeta[row][column]; } } break; @@ -152,8 +156,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 7: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus7coeffAlpha[row][column]; - CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus7coeffBeta[row][column]; + coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus7coeffAlpha[row][column]; + coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus7coeffBeta[row][column]; } } break; @@ -161,8 +165,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 8: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus8coeffAlpha[row][column]; - CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus8coeffBeta[row][column]; + coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus8coeffAlpha[row][column]; + coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus8coeffBeta[row][column]; } } break; @@ -170,8 +174,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 9: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus9coeffAlpha[row][column]; - CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus9coeffBeta[row][column]; + coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus9coeffAlpha[row][column]; + coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus9coeffBeta[row][column]; } } break; @@ -179,8 +183,8 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 10: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus10coeffAlpha[row][column]; - CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus10coeffBeta[row][column]; + coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus10coeffAlpha[row][column]; + coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus10coeffBeta[row][column]; } } break; @@ -188,20 +192,20 @@ void SunSensor::setCalibrationCoefficients(uint8_t Sensornumber) { case 11: for (uint8_t row = 0; row < 9; row++) { for (uint8_t column = 0; column < 10; column++) { - CoeffAlpha[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus11coeffAlpha[row][column]; - CoeffBeta[Sensornumber][row][column] = acsParameters.susHandlingParameters.sus11coeffBeta[row][column]; + coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus11coeffAlpha[row][column]; + coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus11coeffBeta[row][column]; } } break; } } -void SunSensor::Calibration(uint8_t Sensornumber) { +void SunSensor::Calibration(uint8_t susNumber) { float alpha_m, beta_m, alpha_calibrated, beta_calibrated, k, l; uint8_t index; - alpha_m = AlphaBetaRaw[Sensornumber][0]; //[°] - beta_m = AlphaBetaRaw[Sensornumber][1]; //[°] + alpha_m = alphaBetaRaw[susNumber][0]; //[°] + beta_m = alphaBetaRaw[susNumber][1]; //[°] // while loop iterates above all calibration cells to use the different calibration functions in // each cell @@ -212,47 +216,47 @@ void SunSensor::Calibration(uint8_t Sensornumber) { while (l < 3) { l = l + 1; // if-condition to check in which cell the data point has to be - if ((alpha_m > ((CompleteCellWidth * ((k - 1) / 3)) - HalfCellWidth) && - alpha_m < ((CompleteCellWidth * (k / 3)) - HalfCellWidth)) && - (beta_m > ((CompleteCellWidth * ((l - 1) / 3)) - HalfCellWidth) && - beta_m < ((CompleteCellWidth * (l / 3)) - HalfCellWidth))) { + if ((alpha_m > ((completeCellWidth * ((k - 1) / 3)) - halfCellWidth) && + alpha_m < ((completeCellWidth * (k / 3)) - halfCellWidth)) && + (beta_m > ((completeCellWidth * ((l - 1) / 3)) - halfCellWidth) && + beta_m < ((completeCellWidth * (l / 3)) - halfCellWidth))) { index = (3 * (k - 1) + l) - 1; // calculate the index of the datapoint for the right cell // -> first cell has number 0 - AlphaBetaCalibrated[Sensornumber][0] = - CoeffAlpha[Sensornumber][index][0] + CoeffAlpha[Sensornumber][index][1] * alpha_m + CoeffAlpha[Sensornumber][index][2] * beta_m + - CoeffAlpha[Sensornumber][index][3] * alpha_m * alpha_m + CoeffAlpha[Sensornumber][index][4] * alpha_m * beta_m + - CoeffAlpha[Sensornumber][index][5] * beta_m * beta_m + - CoeffAlpha[Sensornumber][index][6] * alpha_m * alpha_m * alpha_m + - CoeffAlpha[Sensornumber][index][7] * alpha_m * alpha_m * beta_m + - CoeffAlpha[Sensornumber][index][8] * alpha_m * beta_m * beta_m + - CoeffAlpha[Sensornumber][index][9] * beta_m * beta_m * beta_m; //[°] - AlphaBetaCalibrated[Sensornumber][1] = - CoeffBeta[Sensornumber][index][0] + CoeffBeta[Sensornumber][index][1] * alpha_m + - CoeffBeta[Sensornumber][index][2] * beta_m + CoeffBeta[Sensornumber][index][3] * alpha_m * alpha_m + - CoeffBeta[Sensornumber][index][4] * alpha_m * beta_m + - CoeffBeta[Sensornumber][index][5] * beta_m * beta_m + - CoeffBeta[Sensornumber][index][6] * alpha_m * alpha_m * alpha_m + - CoeffBeta[Sensornumber][index][7] * alpha_m * alpha_m * beta_m + - CoeffBeta[Sensornumber][index][8] * alpha_m * beta_m * beta_m + - CoeffBeta[Sensornumber][index][9] * beta_m * beta_m * beta_m; //[°] + alphaBetaCalibrated[susNumber][0] = + coeffAlpha[susNumber][index][0] + coeffAlpha[susNumber][index][1] * alpha_m + coeffAlpha[susNumber][index][2] * beta_m + + coeffAlpha[susNumber][index][3] * alpha_m * alpha_m + coeffAlpha[susNumber][index][4] * alpha_m * beta_m + + coeffAlpha[susNumber][index][5] * beta_m * beta_m + + coeffAlpha[susNumber][index][6] * alpha_m * alpha_m * alpha_m + + coeffAlpha[susNumber][index][7] * alpha_m * alpha_m * beta_m + + coeffAlpha[susNumber][index][8] * alpha_m * beta_m * beta_m + + coeffAlpha[susNumber][index][9] * beta_m * beta_m * beta_m; //[°] + alphaBetaCalibrated[susNumber][1] = + coeffBeta[susNumber][index][0] + coeffBeta[susNumber][index][1] * alpha_m + + coeffBeta[susNumber][index][2] * beta_m + coeffBeta[susNumber][index][3] * alpha_m * alpha_m + + coeffBeta[susNumber][index][4] * alpha_m * beta_m + + coeffBeta[susNumber][index][5] * beta_m * beta_m + + coeffBeta[susNumber][index][6] * alpha_m * alpha_m * alpha_m + + coeffBeta[susNumber][index][7] * alpha_m * alpha_m * beta_m + + coeffBeta[susNumber][index][8] * alpha_m * beta_m * beta_m + + coeffBeta[susNumber][index][9] * beta_m * beta_m * beta_m; //[°] } } } } -void SunSensor::CalculateSunVector(uint8_t Sensornumber) { +void SunSensor::CalculateSunVector(uint8_t susNumber) { float alpha, beta; - alpha = AlphaBetaCalibrated[Sensornumber][0]; //[°] - beta = AlphaBetaCalibrated[Sensornumber][1]; //[°] + alpha = alphaBetaCalibrated[susNumber][0]; //[°] + beta = alphaBetaCalibrated[susNumber][1]; //[°] // Calculate the normalized Sun Vector - SunVectorBodyFrame[Sensornumber][0] = + sunVectorBodyFrame[susNumber][0] = (tan(alpha * (M_PI / 180)) / (sqrt((powf(tan(alpha * (M_PI / 180)), 2)) + powf(tan((beta * (M_PI / 180))), 2) + (1)))); - SunVectorBodyFrame[Sensornumber][1] = + sunVectorBodyFrame[susNumber][1] = (tan(beta * (M_PI / 180)) / (sqrt(powf((tan(alpha * (M_PI / 180))), 2) + powf(tan((beta * (M_PI / 180))), 2) + (1)))); - SunVectorBodyFrame[Sensornumber][2] = + sunVectorBodyFrame[susNumber][2] = (-1 / (sqrt(powf((tan(alpha * (M_PI / 180))), 2) + powf((tan(beta * (M_PI / 180))), 2) + (1)))); } @@ -262,79 +266,79 @@ float* SunSensor::getSunVectorBodyFrame() { float* SunVectorBodyFrameReturn = 0; SunVectorBodyFrameReturn = new float[3]; - SunVectorBodyFrameReturn[0] = SunVectorBodyFrame[0]; - SunVectorBodyFrameReturn[1] = SunVectorBodyFrame[1]; - SunVectorBodyFrameReturn[2] = SunVectorBodyFrame[2]; + SunVectorBodyFrameReturn[0] = sunVectorBodyFrame[0]; + SunVectorBodyFrameReturn[1] = sunVectorBodyFrame[1]; + SunVectorBodyFrameReturn[2] = sunVectorBodyFrame[2]; return SunVectorBodyFrameReturn; } -bool SunSensor::getValidityNumber(uint8_t Sensornumber) { - return ValidityNumber[Sensornumber]; +bool SunSensor::getValidFlag(uint8_t susNumber) { + return validFlag[susNumber]; } float* SunSensor::TransferSunVector() { - float* SunVectorEIVE = 0; - SunVectorEIVE = new float[3]; + float* sunVectorEIVE = 0; + sunVectorEIVE = new float[3]; - uint8_t counter = 0; - int8_t BasisMatrixUse[3][3]; - float SunVectorMatrixEIVE[3][12] = {0}, sum; - float SunVectorMatrixBodyFrame[3][12]; + uint8_t susAvail = 12; + int8_t basisMatrixUse[3][3]; + float sunVectorMatrixEIVE[3][12] = {0}; + float sunVectorMatrixBodyFrame[3][12]; - for (uint8_t Sensornumber = 0; Sensornumber < 12; - Sensornumber++) { // save the sun vector of each SUS in their body frame into an array for + for (uint8_t susNumber = 0; susNumber < 12; + susNumber++) { // save the sun vector of each SUS in their body frame into an array for // further processing - float* SunVectorBodyFrame = SunVectorBodyFrame[Sensornumber]; - SunVectorMatrixBodyFrame[0][Sensornumber] = SunVectorBodyFrame[0]; - SunVectorMatrixBodyFrame[1][Sensornumber] = SunVectorBodyFrame[1]; - SunVectorMatrixBodyFrame[2][Sensornumber] = SunVectorBodyFrame[2]; + float* SunVectorBodyFrame = SunVectorBodyFrame[susNumber]; + sunVectorMatrixBodyFrame[0][susNumber] = SunVectorBodyFrame[0]; + sunVectorMatrixBodyFrame[1][susNumber] = SunVectorBodyFrame[1]; + sunVectorMatrixBodyFrame[2][susNumber] = SunVectorBodyFrame[2]; } - for (uint8_t Sensornumber = 0; Sensornumber < 12; Sensornumber++) { - if (getValidityNumber(Sensornumber) == false) { - counter = counter + 1; + for (uint8_t susNumber = 0; susNumber < 12; susNumber++) { + if (getValidFlag(susNumber) == returnvalue::FAILED) { + susAvail -= 1; } // if the SUS data is not valid -> for (uint8_t c1 = 0; c1 < 3; c1++) { for (uint8_t c2 = 0; c2 < 3; c2++) { - switch (Sensornumber) { // find right basis matrix for each SUS + switch (susNumber) { case 0: - BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus0orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus0orientationMatrix[c1][c2]; break; case 1: - BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus1orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus1orientationMatrix[c1][c2]; break; case 2: - BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus2orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus2orientationMatrix[c1][c2]; break; case 3: - BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus3orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus3orientationMatrix[c1][c2]; break; case 4: - BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus4orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus4orientationMatrix[c1][c2]; break; case 5: - BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus5orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus5orientationMatrix[c1][c2]; break; case 6: - BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus6orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus6orientationMatrix[c1][c2]; break; case 7: - BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus7orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus7orientationMatrix[c1][c2]; break; case 8: - BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus8orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus8orientationMatrix[c1][c2]; break; case 9: - BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus9orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus9orientationMatrix[c1][c2]; break; case 10: - BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus10orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus10orientationMatrix[c1][c2]; break; case 11: - BasisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus11orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus11orientationMatrix[c1][c2]; break; } } @@ -344,34 +348,31 @@ float* SunSensor::TransferSunVector() { for (uint8_t p = 0; p < 3; p++) { for (uint8_t q = 0; q < 3; q++) { // normal matrix multiplication - SunVectorMatrixEIVE[p][Sensornumber] += - (BasisMatrixUse[p][q] * SunVectorMatrixBodyFrame[q][Sensornumber]); + sunVectorMatrixEIVE[p][susNumber] += + (basisMatrixUse[p][q] * sunVectorMatrixBodyFrame[q][susNumber]); } } } - if (counter < 12) { // Calculate one sun vector out of all sun vectors from the different SUS + if (susAvail > 0) { // Calculate one sun vector out of all sun vectors from the different SUS for (uint8_t i = 0; i < 3; i++) { - sum = 0; - for (uint8_t Sensornumber = 0; Sensornumber < 12; Sensornumber++) { - if (getValidityNumber(Sensornumber)){ - sum += SunVectorMatrixEIVE[i][Sensornumber]; - //printf("%f\n", SunVectorMatrixEIVE[i][Sensornumber]); + float sum = 0; + for (uint8_t susNumber = 0; susNumber < 12; susNumber++) { + if (getValidFlag(susNumber) == returnvalue::OK){ + sum += sunVectorMatrixEIVE[i][susNumber]; + //printf("%f\n", SunVectorMatrixEIVE[i][susNumber]); } } // ToDo: decide on length on sun vector - SunVectorEIVE[i] = - sum/* / (12 - counter)*/; // FLAG Ergebnis ist falsch, kann an einem Fehler im Programm - // liegen, vermutlich aber an den falschen ChannelValues da die - // transformierten Sonnenvektoren jedes SUS plausibel sind + sunVectorEIVE[i] = sum; } - VectorOperations::normalize(SunVectorEIVE, SunVectorEIVE, 3); + VectorOperations::normalize(sunVectorEIVE, sunVectorEIVE, 3); } else { // No sus is valid throw std::invalid_argument("No sun sensor is valid"); // throw error } - return SunVectorEIVE; + return sunVectorEIVE; } diff --git a/mission/controller/acs/SusConverter.h b/mission/controller/acs/SusConverter.h index 4012bb5a..3a5662ca 100644 --- a/mission/controller/acs/SusConverter.h +++ b/mission/controller/acs/SusConverter.h @@ -8,49 +8,48 @@ #ifndef MISSION_CONTROLLER_ACS_SUSCONVERTER_H_ #define MISSION_CONTROLLER_ACS_SUSCONVERTER_H_ - +#include "AcsParameters.h" #include -#include class SunSensor { public: SunSensor() {} void setSunSensorData(); - void checkSunSensorData(uint8_t Sensornumber); - void AngleCalculation(uint8_t Sensornumber); - void setCalibrationCoefficients(uint8_t Sensornumber); - void Calibration(uint8_t Sensornumber); - void CalculateSunVector(uint8_t Sensornumber); + void checkSunSensorData(uint8_t susNumber); + void calcAngle(uint8_t susNumber); + void setCalibrationCoefficients(uint8_t susNumber); + void Calibration(uint8_t susNumber); + void CalculateSunVector(uint8_t susNumber); - bool getValidityNumber(uint8_t Sensornumber); + bool getValidFlag(uint8_t susNumber); float* getSunVectorBodyFrame(); float* TransferSunVector(); private: uint16_t susChannelValues[12][4]; //[Bit] - float AlphaBetaRaw[12][2]; //[°] - float AlphaBetaCalibrated[12][2]; //[°] - float SunVectorBodyFrame[12][3]; //[-] + float alphaBetaRaw[12][2]; //[°] + float alphaBetaCalibrated[12][2]; //[°] + float sunVectorBodyFrame[12][3]; //[-] - bool ValidityNumber[12] = true; + bool validFlag[12] = returnvalue::OK; - uint16_t ChannelValueCheckHigh = + uint16_t channelValueCheckHigh = 4096; //=2^12[Bit]high borderline for the channel values of one sun sensor for validity Check - uint8_t ChannelValueCheckLow = + uint8_t channelValueCheckLow = 0; //[Bit]low borderline for the channel values of one sun sensor for validity Check - uint16_t ChannelValueSumHigh = + uint16_t channelValueSumHigh = 100; // 4096[Bit]high borderline for check if the sun sensor is illuminated by the sun or by // the reflection of sunlight from the moon/earth - uint8_t ChannelValueSumLow = + uint8_t channelValueSumLow = 0; //[Bit]low borderline for check if the sun sensor is illuminated // by the sun or by the reflection of sunlight from the moon/earth - uint8_t CompleteCellWidth = 140, - HalfCellWidth = 70; //[°] Width of the calibration cells --> necessary for checking in + uint8_t completeCellWidth = 140, + halfCellWidth = 70; //[°] Width of the calibration cells --> necessary for checking in // which cell a data point should be - float CoeffAlpha[12][9][10]; - float CoeffBeta[12][9][10]; + float coeffAlpha[12][9][10]; + float coeffBeta[12][9][10]; AcsParameters acsParameters; }; diff --git a/mission/controller/acs/control/Detumble.cpp b/mission/controller/acs/control/Detumble.cpp index 8a15aa8a..67903c7c 100644 --- a/mission/controller/acs/control/Detumble.cpp +++ b/mission/controller/acs/control/Detumble.cpp @@ -7,13 +7,13 @@ */ -#include +#include "Detumble.h" +#include "../util/MathOperations.h" +#include #include #include -#include #include #include -#include #include diff --git a/mission/controller/acs/control/Detumble.h b/mission/controller/acs/control/Detumble.h index 618be6c6..835c32b0 100644 --- a/mission/controller/acs/control/Detumble.h +++ b/mission/controller/acs/control/Detumble.h @@ -8,14 +8,15 @@ #ifndef ACS_CONTROL_DETUMBLE_H_ #define ACS_CONTROL_DETUMBLE_H_ +#include "../SensorValues.h" +#include "../OutputValues.h" +#include "../AcsParameters.h" +#include "../config/classIds.h" #include #include -#include -#include -#include -#include -#include #include +#include + class Detumble{ diff --git a/mission/controller/acs/control/PtgCtrl.cpp b/mission/controller/acs/control/PtgCtrl.cpp index eaffd909..999df912 100644 --- a/mission/controller/acs/control/PtgCtrl.cpp +++ b/mission/controller/acs/control/PtgCtrl.cpp @@ -8,12 +8,12 @@ #include "PtgCtrl.h" -#include -#include -#include -#include -#include -#include +#include "../util/MathOperations.h" +#include +#include +#include +#include +#include #include PtgCtrl::PtgCtrl(AcsParameters *acsParameters_){ diff --git a/mission/controller/acs/control/PtgCtrl.h b/mission/controller/acs/control/PtgCtrl.h index fe5d0e96..87a66f2d 100644 --- a/mission/controller/acs/control/PtgCtrl.h +++ b/mission/controller/acs/control/PtgCtrl.h @@ -14,12 +14,12 @@ #ifndef PTGCTRL_H_ #define PTGCTRL_H_ +#include "../SensorValues.h" +#include "../OutputValues.h" +#include "../AcsParameters.h" +#include "../config/classIds.h" #include #include -#include -#include -#include -#include #include class PtgCtrl{ @@ -53,7 +53,7 @@ private: AcsParameters::PointingModeControllerParameters* pointingModeControllerParameters; AcsParameters::RwHandlingParameters* rwHandlingParameters; AcsParameters::InertiaEIVE* inertiaEIVE; - AcsParameters::RWMatrices* rwMatrices; + AcsParameters::RwMatrices* rwMatrices; }; #endif /* ACS_CONTROL_PTGCTRL_H_ */ diff --git a/mission/controller/acs/control/SafeCtrl.cpp b/mission/controller/acs/control/SafeCtrl.cpp index 55772ae4..ff619f35 100644 --- a/mission/controller/acs/control/SafeCtrl.cpp +++ b/mission/controller/acs/control/SafeCtrl.cpp @@ -6,12 +6,13 @@ */ #include "SafeCtrl.h" -#include -#include -#include -#include -#include +#include "../util/MathOperations.h" #include +#include +#include +#include +#include + SafeCtrl::SafeCtrl(AcsParameters *acsParameters_){ loadAcsParameters(acsParameters_); diff --git a/mission/controller/acs/control/SafeCtrl.h b/mission/controller/acs/control/SafeCtrl.h index 36807bcc..c6d47324 100644 --- a/mission/controller/acs/control/SafeCtrl.h +++ b/mission/controller/acs/control/SafeCtrl.h @@ -8,14 +8,15 @@ #ifndef SAFECTRL_H_ #define SAFECTRL_H_ +#include "../SensorValues.h" +#include "../OutputValues.h" +#include "../AcsParameters.h" +#include "../config/classIds.h" #include #include -#include -#include -#include -#include "acs/config/classIds.h" -#include #include +#include + class SafeCtrl{ -- 2.34.1 From 4a1cce19c4bb5dc3e53f052c9cde1f288aa691b7 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 27 Sep 2022 11:57:15 +0200 Subject: [PATCH 032/101] fixed minor bugs --- mission/controller/acs/AcsParameters.h | 26 ++++++++++----------- mission/controller/acs/OutputValues.h | 2 +- mission/controller/acs/SensorProcessing.h | 2 +- mission/controller/acs/SusConverter.cpp | 25 ++++---------------- mission/controller/acs/SusConverter.h | 26 +++++++++++++++++---- mission/controller/acs/config/classIds.h | 6 +++-- mission/controller/acs/control/Detumble.h | 2 +- mission/controller/acs/control/SafeCtrl.cpp | 2 +- 8 files changed, 48 insertions(+), 43 deletions(-) diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index d0d67691..cc1fd7b1 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -845,13 +845,13 @@ public: bool avoidBlindStr = true; double blindAvoidStart = 1.5; double blindAvoidStop = 2.5; - double blindRotRate = 1 * Math::PI /180; + double blindRotRate = 1 * M_PI /180; double zeta = 0.3; double zetaLow; double om = 0.3; double omLow; - double omMax = 1 * Math::PI / 180; + double omMax = 1 * M_PI / 180; double qiMin = 0.1; double gainNullspace = 0.01; @@ -867,7 +867,7 @@ public: struct StrParameters { - double exclusionAngle = 20 * Math::PI /180; + double exclusionAngle = 20 * M_PI /180; // double strOrientationMatrix[3][3]; double boresightAxis[3] = { 0.7593, 0.0000,-0.6508}; //in body/geometry frame } strParameters; @@ -876,8 +876,8 @@ public: } gpsParameters; struct GroundStationParameters { - double latitudeGs = 48.7495 * Math::PI / 180.; // [rad] Latitude - double longitudeGs = 9.10384 * Math::PI / 180.; // [rad] Longitude + double latitudeGs = 48.7495 * M_PI / 180.; // [rad] Latitude + double longitudeGs = 9.10384 * M_PI / 180.; // [rad] Longitude double altitudeGs = 500; // [m] Altitude double earthRadiusEquat = 6378137; // [m] double earthRadiusPolar = 6356752.314; // [m] @@ -889,15 +889,15 @@ public: }; uint8_t useSunModel; float domega = 36000.771; - float omega_0 = 282.94 * Math::PI / 180.; //RAAN plus argument of perigee + float omega_0 = 282.94 * M_PI / 180.; //RAAN plus argument of perigee float m_0 = 357.5256; //coefficients for mean anomaly float dm = 35999.049; //coefficients for mean anomaly // ToDo: check correct assignment of e and e1. Both were assigned to e before - float e = 23.4392911 * Math::PI / 180.; //angle of earth's rotation axis - float e1 = 0.74508 * Math::PI / 180.; + float e = 23.4392911 * M_PI / 180.; //angle of earth's rotation axis + float e1 = 0.74508 * M_PI / 180.; // - float p1 = 6892. / 3600. * Math::PI / 180.; //some parameter - float p2 = 72. / 3600. * Math::PI / 180.; //some parameter + float p1 = 6892. / 3600. * M_PI / 180.; //some parameter + float p2 = 72. / 3600. * M_PI / 180.; //some parameter } sunModelParameters; struct KalmanFilterParameters { @@ -907,9 +907,9 @@ public: double processNoiseOmega[3]; double processNoiseQuaternion[4]; - double sensorNoiseSTR = 0.1 * Math::PI / 180; - double sensorNoiseSS = 8 * Math::PI / 180; - double sensorNoiseMAG = 4 * Math::PI / 180; + double sensorNoiseSTR = 0.1 * M_PI / 180; + double sensorNoiseSS = 8 * M_PI / 180; + double sensorNoiseMAG = 4 * M_PI / 180; double sensorNoiseRMU[3]; double sensorNoiseArwRmu; //Angular Random Walk diff --git a/mission/controller/acs/OutputValues.h b/mission/controller/acs/OutputValues.h index a73dc43c..c9fc71f1 100644 --- a/mission/controller/acs/OutputValues.h +++ b/mission/controller/acs/OutputValues.h @@ -48,4 +48,4 @@ public: } -#endif OUTPUTVALUES_H_ +#endif /*OUTPUTVALUES_H_*/ diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h index aa4dc3bd..097c88ed 100644 --- a/mission/controller/acs/SensorProcessing.h +++ b/mission/controller/acs/SensorProcessing.h @@ -86,5 +86,5 @@ protected: }; -#endif SENSORPROCESSING_H_ +#endif /*SENSORPROCESSING_H_*/ diff --git a/mission/controller/acs/SusConverter.cpp b/mission/controller/acs/SusConverter.cpp index c2d65133..13f23808 100644 --- a/mission/controller/acs/SusConverter.cpp +++ b/mission/controller/acs/SusConverter.cpp @@ -12,21 +12,6 @@ #include #include -void SunSensor::setSunSensorData() { - // ToDo: exchange dummy values with DataPool - susChannelValues[0] = {3913, 3912, 3799, 4056}; - susChannelValues[1] = {3913, 3912, 3799, 4056}; - susChannelValues[2] = {3913, 3912, 3799, 4056}; - susChannelValues[3] = {3913, 3912, 3799, 4056}; - susChannelValues[4] = {3913, 3912, 3799, 4056}; - susChannelValues[5] = {3913, 3912, 3799, 4056}; - susChannelValues[6] = {3913, 3912, 3799, 4056}; - susChannelValues[7] = {3913, 3912, 3799, 4056}; - susChannelValues[8] = {3913, 3912, 3799, 4056}; - susChannelValues[9] = {3913, 3912, 3799, 4056}; - susChannelValues[10] = {3913, 3912, 3799, 4056}; - susChannelValues[11] = {3913, 3912, 3799, 4056}; -} void SunSensor::checkSunSensorData(uint8_t susNumber) { uint16_t channelValueSum; @@ -261,14 +246,14 @@ void SunSensor::CalculateSunVector(uint8_t susNumber) { (sqrt(powf((tan(alpha * (M_PI / 180))), 2) + powf((tan(beta * (M_PI / 180))), 2) + (1)))); } -float* SunSensor::getSunVectorBodyFrame() { +float* SunSensor::getSunVectorBodyFrame(uint8_t susNumber) { // return function for the sun vector in the body frame float* SunVectorBodyFrameReturn = 0; SunVectorBodyFrameReturn = new float[3]; - SunVectorBodyFrameReturn[0] = sunVectorBodyFrame[0]; - SunVectorBodyFrameReturn[1] = sunVectorBodyFrame[1]; - SunVectorBodyFrameReturn[2] = sunVectorBodyFrame[2]; + SunVectorBodyFrameReturn[0] = sunVectorBodyFrame[susNumber][0]; + SunVectorBodyFrameReturn[1] = sunVectorBodyFrame[susNumber][1]; + SunVectorBodyFrameReturn[2] = sunVectorBodyFrame[susNumber][2]; return SunVectorBodyFrameReturn; } @@ -289,7 +274,7 @@ float* SunSensor::TransferSunVector() { for (uint8_t susNumber = 0; susNumber < 12; susNumber++) { // save the sun vector of each SUS in their body frame into an array for // further processing - float* SunVectorBodyFrame = SunVectorBodyFrame[susNumber]; + float* SunVectorBodyFrame = &SunVectorBodyFrame[susNumber]; sunVectorMatrixBodyFrame[0][susNumber] = SunVectorBodyFrame[0]; sunVectorMatrixBodyFrame[1][susNumber] = SunVectorBodyFrame[1]; sunVectorMatrixBodyFrame[2][susNumber] = SunVectorBodyFrame[2]; diff --git a/mission/controller/acs/SusConverter.h b/mission/controller/acs/SusConverter.h index 3a5662ca..bfec1dfe 100644 --- a/mission/controller/acs/SusConverter.h +++ b/mission/controller/acs/SusConverter.h @@ -15,7 +15,6 @@ class SunSensor { public: SunSensor() {} - void setSunSensorData(); void checkSunSensorData(uint8_t susNumber); void calcAngle(uint8_t susNumber); void setCalibrationCoefficients(uint8_t susNumber); @@ -23,16 +22,35 @@ class SunSensor { void CalculateSunVector(uint8_t susNumber); bool getValidFlag(uint8_t susNumber); - float* getSunVectorBodyFrame(); + float* getSunVectorBodyFrame(uint8_t susNumber); float* TransferSunVector(); private: - uint16_t susChannelValues[12][4]; //[Bit] + // ToDo: remove statics and replace with actual data + uint16_t susChannelValues[12][4] = { + {3913, 3912, 3799, 4056}, + {3913, 3912, 3799, 4056}, + {3913, 3912, 3799, 4056}, + {3913, 3912, 3799, 4056}, + {3913, 3912, 3799, 4056}, + {3913, 3912, 3799, 4056}, + {3913, 3912, 3799, 4056}, + {3913, 3912, 3799, 4056}, + {3913, 3912, 3799, 4056}, + {3913, 3912, 3799, 4056}, + {3913, 3912, 3799, 4056}, + {3913, 3912, 3799, 4056}}; //[Bit] float alphaBetaRaw[12][2]; //[°] float alphaBetaCalibrated[12][2]; //[°] float sunVectorBodyFrame[12][3]; //[-] - bool validFlag[12] = returnvalue::OK; + bool validFlag[12] = {returnvalue::OK, + returnvalue::OK,returnvalue::OK, + returnvalue::OK,returnvalue::OK, + returnvalue::OK,returnvalue::OK, + returnvalue::OK,returnvalue::OK, + returnvalue::OK,returnvalue::OK, + returnvalue::OK}; uint16_t channelValueCheckHigh = 4096; //=2^12[Bit]high borderline for the channel values of one sun sensor for validity Check diff --git a/mission/controller/acs/config/classIds.h b/mission/controller/acs/config/classIds.h index 0c03b408..7db1ea72 100644 --- a/mission/controller/acs/config/classIds.h +++ b/mission/controller/acs/config/classIds.h @@ -7,11 +7,13 @@ #ifndef ACS_CONFIG_CLASSIDS_H_ #define ACS_CONFIG_CLASSIDS_H_ -#include "bsp_hosted/fsfwconfig/returnvalues/classIds.h" + +#include +#include namespace CLASS_ID { enum eiveclassIds: uint8_t { - EIVE_CLASS_ID_START = CLASS_ID_END, + EIVE_CLASS_ID_START = COMMON_CLASS_ID_END, KALMAN, SAFE, PTG, diff --git a/mission/controller/acs/control/Detumble.h b/mission/controller/acs/control/Detumble.h index 835c32b0..b85aaf86 100644 --- a/mission/controller/acs/control/Detumble.h +++ b/mission/controller/acs/control/Detumble.h @@ -43,5 +43,5 @@ private: AcsParameters::MagnetorquesParameter* magnetorquesParameter; }; -#endif ACS_CONTROL_DETUMBLE_H_ +#endif /*ACS_CONTROL_DETUMBLE_H_*/ diff --git a/mission/controller/acs/control/SafeCtrl.cpp b/mission/controller/acs/control/SafeCtrl.cpp index ff619f35..32029ad7 100644 --- a/mission/controller/acs/control/SafeCtrl.cpp +++ b/mission/controller/acs/control/SafeCtrl.cpp @@ -85,7 +85,7 @@ ReturnValue_t SafeCtrl::safeMekf(timeval now, double *quatBJ, bool *quatBJValid, VectorOperations::mulScalar(torqueMgt, 1/pow(normMag,2), outputMagMomB, 3); *outputValid = true; - return RETURN_OK; + return returnvalue::OK; } -- 2.34.1 From eb08d8849b631e9e5b08f496ddd571902da0a7b0 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 28 Sep 2022 15:27:51 +0200 Subject: [PATCH 033/101] added SUS datapool to AcsController --- mission/controller/AcsController.cpp | 83 ++++++++++++++++++- mission/controller/AcsController.h | 18 ++++ .../AcsCtrlDefinitions.h | 17 +++- 3 files changed, 115 insertions(+), 3 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 09e91e26..bfce1d48 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -3,7 +3,7 @@ #include AcsController::AcsController(object_id_t objectId) - : ExtendedControllerBase(objectId, objects::NO_OBJECT), mgmData(this) {} + : ExtendedControllerBase(objectId, objects::NO_OBJECT), mgmData(this), susData(this) {} ReturnValue_t AcsController::handleCommandMessage(CommandMessage *message) { return returnvalue::OK; @@ -35,6 +35,12 @@ void AcsController::performControlOperation() { copyMgmData(); } } + { + PoolReadGuard pg(&susData); + if (pg.getReadResult() == returnvalue::OK) { + copySusData(); + } + } } ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, @@ -94,3 +100,78 @@ void AcsController::copyMgmData() { } } } + +void AcsController::copySusData() { + { + PoolReadGuard pg(&susSets[0]); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susData.sus0.value, susSets[0].channels.value, 6 * sizeof(uint16_t)); + } + } + { + PoolReadGuard pg(&susSets[1]); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susData.sus1.value, susSets[1].channels.value, 6 * sizeof(uint16_t)); + } + } + { + PoolReadGuard pg(&susSets[2]); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susData.sus2.value, susSets[2].channels.value, 6 * sizeof(uint16_t)); + } + } + { + PoolReadGuard pg(&susSets[3]); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susData.sus3.value, susSets[3].channels.value, 6 * sizeof(uint16_t)); + } + } + { + PoolReadGuard pg(&susSets[4]); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susData.sus4.value, susSets[4].channels.value, 6 * sizeof(uint16_t)); + } + } + { + PoolReadGuard pg(&susSets[5]); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susData.sus5.value, susSets[5].channels.value, 6 * sizeof(uint16_t)); + } + } + { + PoolReadGuard pg(&susSets[6]); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susData.sus6.value, susSets[6].channels.value, 6 * sizeof(uint16_t)); + } + } + { + PoolReadGuard pg(&susSets[7]); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susData.sus7.value, susSets[7].channels.value, 6 * sizeof(uint16_t)); + } + } + { + PoolReadGuard pg(&susSets[8]); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susData.sus8.value, susSets[8].channels.value, 6 * sizeof(uint16_t)); + } + } + { + PoolReadGuard pg(&susSets[9]); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susData.sus9.value, susSets[9].channels.value, 6 * sizeof(uint16_t)); + } + } + { + PoolReadGuard pg(&susSets[10]); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susData.sus10.value, susSets[10].channels.value, 6 * sizeof(uint16_t)); + } + } + { + PoolReadGuard pg(&susSets[11]); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susData.sus11.value, susSets[11].channels.value, 6 * sizeof(uint16_t)); + } + } +} diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index 14b710a2..210b1c04 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -55,6 +55,9 @@ class AcsController : public ExtendedControllerBase { void copyMgmData(); // Sun Sensors + + acsctrl::SusDataRaw susData; + std::array susSets{ SUS::SusDataset(objects::SUS_0_N_LOC_XFYFZM_PT_XF), SUS::SusDataset(objects::SUS_1_N_LOC_XBYFZM_PT_XB), @@ -70,6 +73,21 @@ class AcsController : public ExtendedControllerBase { SUS::SusDataset(objects::SUS_11_R_LOC_XBYMZB_PT_ZB), }; + PoolEntry sus0PoolVec = PoolEntry(6); + PoolEntry sus1PoolVec = PoolEntry(6); + PoolEntry sus2PoolVec = PoolEntry(6); + PoolEntry sus3PoolVec = PoolEntry(6); + PoolEntry sus4PoolVec = PoolEntry(6); + PoolEntry sus5PoolVec = PoolEntry(6); + PoolEntry sus6PoolVec = PoolEntry(6); + PoolEntry sus7PoolVec = PoolEntry(6); + PoolEntry sus8PoolVec = PoolEntry(6); + PoolEntry sus9PoolVec = PoolEntry(6); + PoolEntry sus10PoolVec = PoolEntry(6); + PoolEntry sus11PoolVec = PoolEntry(6); + + void copySusData(); + // Initial delay to make sure all pool variables have been initialized their owners Countdown initialCountdown = Countdown(INIT_DELAY); }; diff --git a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h index 9a2b1abd..1b38e033 100644 --- a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h +++ b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h @@ -60,9 +60,22 @@ class MgmDataRaw : public StaticLocalDataSet { private: }; -class SusData : public StaticLocalDataSet { +class SusDataRaw : public StaticLocalDataSet { public: - SusData(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, SUS_SENSOR_DATA) {} + SusDataRaw(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, SUS_SENSOR_DATA) {} + + lp_vec_t sus0 = lp_vec_t(sid.objectId, SUS_0_N_LOC_XFYFZM_PT_XF, this); + lp_vec_t sus1 = lp_vec_t(sid.objectId, SUS_1_N_LOC_XBYFZM_PT_XB, this); + lp_vec_t sus2 = lp_vec_t(sid.objectId, SUS_2_N_LOC_XFYBZB_PT_YB, this); + lp_vec_t sus3 = lp_vec_t(sid.objectId, SUS_3_N_LOC_XFYBZF_PT_YF, this); + lp_vec_t sus4 = lp_vec_t(sid.objectId, SUS_4_N_LOC_XMYFZF_PT_ZF, this); + lp_vec_t sus5 = lp_vec_t(sid.objectId, SUS_5_N_LOC_XFYMZB_PT_ZB, this); + lp_vec_t sus6 = lp_vec_t(sid.objectId, SUS_6_R_LOC_XFYBZM_PT_XF, this); + lp_vec_t sus7 = lp_vec_t(sid.objectId, SUS_7_R_LOC_XBYBZM_PT_XB, this); + lp_vec_t sus8 = lp_vec_t(sid.objectId, SUS_8_R_LOC_XBYBZB_PT_YB, this); + lp_vec_t sus9 = lp_vec_t(sid.objectId, SUS_9_R_LOC_XBYBZB_PT_YF, this); + lp_vec_t sus10 = lp_vec_t(sid.objectId, SUS_10_N_LOC_XMYBZF_PT_ZF, this); + lp_vec_t sus11 = lp_vec_t(sid.objectId, SUS_11_R_LOC_XBYMZB_PT_ZB, this); private: }; -- 2.34.1 From 16429009b4013ba67c3f6109eec47191445eb36f Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Fri, 30 Sep 2022 10:13:27 +0200 Subject: [PATCH 034/101] added LocalDataPool entries --- dummies/ImtqDummy.cpp | 2 ++ dummies/MgmLIS3MDLDummy.cpp | 1 + dummies/MgmRm3100Dummy.cpp | 3 ++- mission/controller/AcsController.cpp | 8 ++++++-- 4 files changed, 11 insertions(+), 3 deletions(-) diff --git a/dummies/ImtqDummy.cpp b/dummies/ImtqDummy.cpp index 6dc451b3..63d05c1e 100644 --- a/dummies/ImtqDummy.cpp +++ b/dummies/ImtqDummy.cpp @@ -39,5 +39,7 @@ uint32_t ImtqDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { retur ReturnValue_t ImtqDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { localDataPoolMap.emplace(IMTQ::MCU_TEMPERATURE, new PoolEntry({0})); + localDataPoolMap.emplace(IMTQ::MGM_CAL_NT, new PoolEntry({0.0,0.0,0.0})); + localDataPoolMap.emplace(IMTQ::ACTUATION_CAL_STATUS, new PoolEntry({0})); return returnvalue::OK; } diff --git a/dummies/MgmLIS3MDLDummy.cpp b/dummies/MgmLIS3MDLDummy.cpp index 7aa5fdf7..9c521559 100644 --- a/dummies/MgmLIS3MDLDummy.cpp +++ b/dummies/MgmLIS3MDLDummy.cpp @@ -41,5 +41,6 @@ uint32_t MgmLIS3MDLDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { ReturnValue_t MgmLIS3MDLDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { localDataPoolMap.emplace(MGMLIS3MDL::TEMPERATURE_CELCIUS, new PoolEntry({0.0})); + localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTHS, new PoolEntry({0.0,0.0,0.0})); return returnvalue::OK; } diff --git a/dummies/MgmRm3100Dummy.cpp b/dummies/MgmRm3100Dummy.cpp index ad97e7be..cb27209c 100644 --- a/dummies/MgmRm3100Dummy.cpp +++ b/dummies/MgmRm3100Dummy.cpp @@ -36,5 +36,6 @@ uint32_t MgmRm3100Dummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { ReturnValue_t MgmRm3100Dummy::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) { - return OK; + localDataPoolMap.emplace(RM3100::FIELD_STRENGTHS, new PoolEntry({0.0, 0.0, 0.0})); + return returnvalue::OK; } diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index bfce1d48..896af482 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -2,6 +2,8 @@ #include +#include + AcsController::AcsController(object_id_t objectId) : ExtendedControllerBase(objectId, objects::NO_OBJECT), mgmData(this), susData(this) {} @@ -29,7 +31,7 @@ void AcsController::performControlOperation() { break; } - { + /*{ PoolReadGuard pg(&mgmData); if (pg.getReadResult() == returnvalue::OK) { copyMgmData(); @@ -40,7 +42,7 @@ void AcsController::performControlOperation() { if (pg.getReadResult() == returnvalue::OK) { copySusData(); } - } + }*/ } ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, @@ -58,6 +60,8 @@ ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localD LocalPoolDataSetBase *AcsController::getDataSetHandle(sid_t sid) { if (sid == mgmData.getSid()) { return &mgmData; + } else if (sid == susData.getSid()) { + return &susData; } return nullptr; } -- 2.34.1 From abe5f43ae95d7eadf9e958f9e7ff4b3bf7682a18 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Fri, 30 Sep 2022 11:06:17 +0200 Subject: [PATCH 035/101] added performDetumble and implemented ckeckModeCommand --- mission/controller/AcsController.cpp | 61 ++++++++++++++++++++++++++-- mission/controller/AcsController.h | 21 ++++++++++ 2 files changed, 78 insertions(+), 4 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 896af482..26f6a1ee 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -1,11 +1,14 @@ #include "AcsController.h" #include - -#include +#include AcsController::AcsController(object_id_t objectId) - : ExtendedControllerBase(objectId, objects::NO_OBJECT), mgmData(this), susData(this) {} + : ExtendedControllerBase(objectId, objects::NO_OBJECT), + mgmData(this), + susData(this), + sensorProcessing(&acsParameters), + detumbleCounter{0} {} ReturnValue_t AcsController::handleCommandMessage(CommandMessage *message) { return returnvalue::OK; @@ -45,6 +48,43 @@ void AcsController::performControlOperation() { }*/ } +void AcsController::performDetumble() { + ACS::SensorValues sensorValues; + ACS::OutputValues outputValues; + + // sensorValues.read(); + // outputValues.read(); + + timeval now; // = {0,0}; + Clock::getClock_timeval(&now); + + sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); + ReturnValue_t validMekf; + navigation.useMekf(&sensorValues, &outputValues, &validMekf); + double magMomMtq[3] = {0, 0, 0}; + detumble.bDotLaw(outputValues.magneticFieldVectorDerivative, + &outputValues.magneticFieldVectorDerivativeValid, outputValues.magFieldEst, + &outputValues.magFieldEstValid, magMomMtq); + double dipolCmdUnits[3] = {0, 0, 0}; + actuatorCmd.cmdDipolMtq(magMomMtq, dipolCmdUnits); + + if (outputValues.satRateMekfValid && VectorOperations::norm(outputValues.satRateMekf, 3) < + acsParameters.detumbleParameter.omegaDetumbleEnd) { + detumbleCounter++; + } + + else if (outputValues.satRateEstValid && + VectorOperations::norm(outputValues.satRateEst, 3) < + acsParameters.detumbleParameter.omegaDetumbleEnd) { + detumbleCounter++; + } + + if (detumbleCounter > acsParameters.detumbleParameter.detumblecounter) { + submode = SUBMODE_SAFE; + detumbleCounter = 0; + } +} + ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { localDataPoolMap.emplace(acsctrl::PoolIds::MGM_0_LIS3_UT, &mgm0PoolVec); @@ -68,7 +108,20 @@ LocalPoolDataSetBase *AcsController::getDataSetHandle(sid_t sid) { ReturnValue_t AcsController::checkModeCommand(Mode_t mode, Submode_t submode, uint32_t *msToReachTheMode) { - return returnvalue::OK; + if (mode == MODE_OFF) { + if (submode == SUBMODE_NONE) { + return returnvalue::OK; + } else { + return INVALID_SUBMODE; + } + } else if ((mode == MODE_ON) || (mode == MODE_NORMAL)) { + if ((submode > 5) || (submode < 2)) { + return INVALID_SUBMODE; + } else { + return returnvalue::OK; + } + } + return INVALID_MODE; } void AcsController::copyMgmData() { diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index 210b1c04..21c77683 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -3,7 +3,12 @@ #include #include +#include +#include "acs/ActuatorCmd.h" +#include "acs/Navigation.h" +#include "acs/SensorProcessing.h" +#include "acs/control/Detumble.h" #include "controllerdefinitions/AcsCtrlDefinitions.h" #include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" #include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" @@ -16,7 +21,23 @@ class AcsController : public ExtendedControllerBase { AcsController(object_id_t objectId); + static const Submode_t SUBMODE_SAFE = 2; + static const Submode_t SUBMODE_DETUMBLE = 3; + static const Submode_t SUBMODE_PTG_GS = 4; + static const Submode_t SUBMODE_PTG_NADIR = 5; + + protected: + void performDetumble(); + private: + AcsParameters acsParameters; + SensorProcessing sensorProcessing; + Navigation navigation; + ActuatorCmd actuatorCmd; + + Detumble detumble; + uint8_t detumbleCounter; + enum class InternalState { STARTUP, INITIAL_DELAY, READY }; InternalState internalState = InternalState::STARTUP; -- 2.34.1 From 9d0e10eb1ed11b6f998a03dd22696af0a6e2c084 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 4 Oct 2022 13:45:13 +0200 Subject: [PATCH 036/101] fixed dummies, scheduled dummies as part of acsTask --- bsp_q7s/core/InitMission.cpp | 19 ++++++++ dummies/ImtqDummy.cpp | 2 + dummies/MgmLIS3MDLDummy.cpp | 2 +- dummies/SusDummy.cpp | 3 +- mission/controller/AcsController.cpp | 61 ++++++++++++++++++++---- mission/controller/AcsController.h | 9 +++- mission/controller/acs/AcsParameters.cpp | 15 +++--- mission/controller/acs/AcsParameters.h | 2 +- 8 files changed, 92 insertions(+), 21 deletions(-) diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index e60c2caf..5bac228b 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -139,6 +139,25 @@ void initmission::initTasks() { initmission::printAddObjectError("ACS_CTRL", objects::ACS_CONTROLLER); } #endif +#if OBSW_Q7S_EM == 1 + acsTask->addComponent(objects::MGM_0_LIS3_HANDLER); + acsTask->addComponent(objects::MGM_1_RM3100_HANDLER); + acsTask->addComponent(objects::MGM_2_LIS3_HANDLER); + acsTask->addComponent(objects::MGM_3_RM3100_HANDLER); + acsTask->addComponent(objects::IMTQ_HANDLER); + acsTask->addComponent(objects::SUS_0_N_LOC_XFYFZM_PT_XF); + acsTask->addComponent(objects::SUS_6_R_LOC_XFYBZM_PT_XF); + acsTask->addComponent(objects::SUS_1_N_LOC_XBYFZM_PT_XB); + acsTask->addComponent(objects::SUS_7_R_LOC_XBYBZM_PT_XB); + acsTask->addComponent(objects::SUS_2_N_LOC_XFYBZB_PT_YB); + acsTask->addComponent(objects::SUS_8_R_LOC_XBYBZB_PT_YB); + acsTask->addComponent(objects::SUS_3_N_LOC_XFYBZF_PT_YF); + acsTask->addComponent(objects::SUS_9_R_LOC_XBYBZB_PT_YF); + acsTask->addComponent(objects::SUS_4_N_LOC_XMYFZF_PT_ZF); + acsTask->addComponent(objects::SUS_10_N_LOC_XMYBZF_PT_ZF); + acsTask->addComponent(objects::SUS_5_N_LOC_XFYMZB_PT_ZB); + acsTask->addComponent(objects::SUS_11_R_LOC_XBYMZB_PT_ZB); +#endif PeriodicTaskIF* sysTask = factory->createPeriodicTask( "SYS_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc); diff --git a/dummies/ImtqDummy.cpp b/dummies/ImtqDummy.cpp index 63d05c1e..8765e978 100644 --- a/dummies/ImtqDummy.cpp +++ b/dummies/ImtqDummy.cpp @@ -41,5 +41,7 @@ ReturnValue_t ImtqDummy::initializeLocalDataPool(localpool::DataPool &localDataP localDataPoolMap.emplace(IMTQ::MCU_TEMPERATURE, new PoolEntry({0})); localDataPoolMap.emplace(IMTQ::MGM_CAL_NT, new PoolEntry({0.0,0.0,0.0})); localDataPoolMap.emplace(IMTQ::ACTUATION_CAL_STATUS, new PoolEntry({0})); + localDataPoolMap.emplace(IMTQ::MTM_RAW, new PoolEntry({0.0,0.0,0.0})); + localDataPoolMap.emplace(IMTQ::ACTUATION_RAW_STATUS, new PoolEntry({0})); return returnvalue::OK; } diff --git a/dummies/MgmLIS3MDLDummy.cpp b/dummies/MgmLIS3MDLDummy.cpp index 9c521559..b89d74b8 100644 --- a/dummies/MgmLIS3MDLDummy.cpp +++ b/dummies/MgmLIS3MDLDummy.cpp @@ -41,6 +41,6 @@ uint32_t MgmLIS3MDLDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { ReturnValue_t MgmLIS3MDLDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { localDataPoolMap.emplace(MGMLIS3MDL::TEMPERATURE_CELCIUS, new PoolEntry({0.0})); - localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTHS, new PoolEntry({0.0,0.0,0.0})); + localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTHS, new PoolEntry({0.0, 0.0, 0.0})); return returnvalue::OK; } diff --git a/dummies/SusDummy.cpp b/dummies/SusDummy.cpp index 2a2a1bda..10368a9a 100644 --- a/dummies/SusDummy.cpp +++ b/dummies/SusDummy.cpp @@ -54,7 +54,8 @@ void SusDummy::performControlOperation() { ReturnValue_t SusDummy::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) { localDataPoolMap.emplace(SUS::SusPoolIds::TEMPERATURE_C, new PoolEntry({0}, 1, true)); - localDataPoolMap.emplace(SUS::SusPoolIds::CHANNEL_VEC, new PoolEntry({0})); + localDataPoolMap.emplace(SUS::SusPoolIds::CHANNEL_VEC, + new PoolEntry({0, 0, 0, 0, 0, 0})); return returnvalue::OK; } diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 26f6a1ee..8c92d968 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -1,14 +1,17 @@ #include "AcsController.h" #include -#include +//#include AcsController::AcsController(object_id_t objectId) : ExtendedControllerBase(objectId, objects::NO_OBJECT), + /*sensorProcessing(&acsParameters), + navigation(&acsParameters), + actuatorCmd(&acsParameters), + detumble(&acsParameters), + detumbleCounter{0},*/ mgmData(this), - susData(this), - sensorProcessing(&acsParameters), - detumbleCounter{0} {} + susData(this) {} ReturnValue_t AcsController::handleCommandMessage(CommandMessage *message) { return returnvalue::OK; @@ -28,13 +31,28 @@ void AcsController::performControlOperation() { return; } case InternalState::READY: { + if (mode != MODE_OFF) { + switch (submode) { + case SUBMODE_SAFE: + // performSafe(); + break; + + case SUBMODE_DETUMBLE: + // performDetumble(); + break; + + case SUBMODE_PTG_GS: + // performPointingCtrl(); + break; + } + } break; } default: break; } - /*{ + { PoolReadGuard pg(&mgmData); if (pg.getReadResult() == returnvalue::OK) { copyMgmData(); @@ -45,11 +63,15 @@ void AcsController::performControlOperation() { if (pg.getReadResult() == returnvalue::OK) { copySusData(); } - }*/ + } +} + +void AcsController::performSafe(){ + } void AcsController::performDetumble() { - ACS::SensorValues sensorValues; + /*ACS::SensorValues sensorValues; ACS::OutputValues outputValues; // sensorValues.read(); @@ -82,17 +104,36 @@ void AcsController::performDetumble() { if (detumbleCounter > acsParameters.detumbleParameter.detumblecounter) { submode = SUBMODE_SAFE; detumbleCounter = 0; - } + }*/ +} + +void AcsController::performPointingCtrl(){ + } ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { + // MGM localDataPoolMap.emplace(acsctrl::PoolIds::MGM_0_LIS3_UT, &mgm0PoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_1_RM3100_UT, &mgm1PoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_2_LIS3_UT, &mgm2PoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_3_RM3100_UT, &mgm3PoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_NT, &imtqMgmPoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_ACT_STATUS, &imtqCalActStatus); + // SUS + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_0_N_LOC_XFYFZM_PT_XF, &sus0PoolVec); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_1_N_LOC_XBYFZM_PT_XB, &sus1PoolVec); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_2_N_LOC_XFYBZB_PT_YB, &sus2PoolVec); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_3_N_LOC_XFYBZF_PT_YF, &sus3PoolVec); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_4_N_LOC_XMYFZF_PT_ZF, &sus4PoolVec); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_5_N_LOC_XFYMZB_PT_ZB, &sus5PoolVec); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_6_R_LOC_XFYBZM_PT_XF, &sus6PoolVec); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_7_R_LOC_XBYBZM_PT_XB, &sus7PoolVec); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_8_R_LOC_XBYBZB_PT_YB, &sus8PoolVec); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_9_R_LOC_XBYBZB_PT_YF, &sus9PoolVec); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_10_N_LOC_XMYBZF_PT_ZF, &sus10PoolVec); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_11_R_LOC_XBYMZB_PT_ZB, &sus11PoolVec); + poolManager.subscribeForRegularPeriodicPacket({mgmData.getSid(), false, 5.0}); return returnvalue::OK; } @@ -124,6 +165,10 @@ ReturnValue_t AcsController::checkModeCommand(Mode_t mode, Submode_t submode, return INVALID_MODE; } +void AcsController::modeChanged(Mode_t mode, Submode_t submode) {} + +void AcsController::announceMode(bool recursive) {} + void AcsController::copyMgmData() { { PoolReadGuard pg(&mgm0Lis3Set); diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index 21c77683..054f2b8f 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -27,16 +27,19 @@ class AcsController : public ExtendedControllerBase { static const Submode_t SUBMODE_PTG_NADIR = 5; protected: + + void performSafe(); void performDetumble(); + void performPointingCtrl(); private: - AcsParameters acsParameters; + /*AcsParameters acsParameters; SensorProcessing sensorProcessing; Navigation navigation; ActuatorCmd actuatorCmd; Detumble detumble; - uint8_t detumbleCounter; + uint8_t detumbleCounter;*/ enum class InternalState { STARTUP, INITIAL_DELAY, READY }; @@ -52,6 +55,8 @@ class AcsController : public ExtendedControllerBase { // Mode abstract functions ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, uint32_t* msToReachTheMode) override; + void modeChanged(Mode_t mode, Submode_t submode); + void announceMode(bool recursive); // MGMs acsctrl::MgmDataRaw mgmData; diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index c22e8ede..0b516c13 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -1,18 +1,17 @@ -#include #include "AcsParameters.h" +#include #include + #include AcsParameters::AcsParameters() {} AcsParameters::~AcsParameters() {} - /* -ReturnValue_t AcsParameters::getParameter(uint8_t domainId, - uint16_t parameterId, ParameterWrapper* parameterWrapper, - const ParameterWrapper *newValues, uint16_t startAtIndex) { - - return 0; - +ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint16_t parameterId, + ParameterWrapper* parameterWrapper, + const ParameterWrapper* newValues, + uint16_t startAtIndex) { + return returnvalue::OK; }*/ diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index cc1fd7b1..39f2c3c6 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -11,7 +11,7 @@ typedef unsigned char uint8_t; -class AcsParameters/*:public HasParametersIF*/{ +class AcsParameters /*: public HasParametersIF*/{ public: AcsParameters(); -- 2.34.1 From 1844df2195a32373cc305d4f6c015c1d336b13fd Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 6 Oct 2022 15:33:01 +0200 Subject: [PATCH 037/101] SusDummy output matched to student test case --- dummies/SusDummy.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/dummies/SusDummy.cpp b/dummies/SusDummy.cpp index 10368a9a..ba267d61 100644 --- a/dummies/SusDummy.cpp +++ b/dummies/SusDummy.cpp @@ -48,6 +48,10 @@ void SusDummy::performControlOperation() { } else { susSet.setValidity(true, true); } + susSet.channels[0] = 3913; + susSet.channels[1] = 3912; + susSet.channels[2] = 3799; + susSet.channels[3] = 4056; susSet.commit(); } -- 2.34.1 From 84e960a9efc55789773db4f2a43d40d749507562 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 6 Oct 2022 15:37:41 +0200 Subject: [PATCH 038/101] enabled performSafe --- mission/controller/AcsController.cpp | 30 ++++++++++++++-------------- mission/controller/AcsController.h | 4 ++-- 2 files changed, 17 insertions(+), 17 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 8c92d968..2b0689c7 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -5,11 +5,11 @@ AcsController::AcsController(object_id_t objectId) : ExtendedControllerBase(objectId, objects::NO_OBJECT), - /*sensorProcessing(&acsParameters), - navigation(&acsParameters), - actuatorCmd(&acsParameters), - detumble(&acsParameters), - detumbleCounter{0},*/ + sensorProcessing(&acsParameters), + navigation(&acsParameters), + actuatorCmd(&acsParameters), + detumble(&acsParameters), + detumbleCounter{0}, mgmData(this), susData(this) {} @@ -64,14 +64,16 @@ void AcsController::performControlOperation() { copySusData(); } } + sif::debug << susData.sus0.value[0] << "," << susData.sus0.value[1] << "," + << susData.sus0.value[2] << "," << susData.sus0.value[3] << "," + << susData.sus0.value[4] << "," << susData.sus0.value[5] << std::endl; + sif::debug << susData.sus0.isValid() << std::endl; } -void AcsController::performSafe(){ - -} +void AcsController::performSafe() {} void AcsController::performDetumble() { - /*ACS::SensorValues sensorValues; + ACS::SensorValues sensorValues; ACS::OutputValues outputValues; // sensorValues.read(); @@ -104,12 +106,10 @@ void AcsController::performDetumble() { if (detumbleCounter > acsParameters.detumbleParameter.detumblecounter) { submode = SUBMODE_SAFE; detumbleCounter = 0; - }*/ + } } -void AcsController::performPointingCtrl(){ - -} +void AcsController::performPointingCtrl() {} ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { @@ -120,6 +120,7 @@ ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localD localDataPoolMap.emplace(acsctrl::PoolIds::MGM_3_RM3100_UT, &mgm3PoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_NT, &imtqMgmPoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_ACT_STATUS, &imtqCalActStatus); + poolManager.subscribeForRegularPeriodicPacket({mgmData.getSid(), false, 5.0}); // SUS localDataPoolMap.emplace(acsctrl::PoolIds::SUS_0_N_LOC_XFYFZM_PT_XF, &sus0PoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::SUS_1_N_LOC_XBYFZM_PT_XB, &sus1PoolVec); @@ -133,8 +134,7 @@ ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localD localDataPoolMap.emplace(acsctrl::PoolIds::SUS_9_R_LOC_XBYBZB_PT_YF, &sus9PoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::SUS_10_N_LOC_XMYBZF_PT_ZF, &sus10PoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::SUS_11_R_LOC_XBYMZB_PT_ZB, &sus11PoolVec); - - poolManager.subscribeForRegularPeriodicPacket({mgmData.getSid(), false, 5.0}); + poolManager.subscribeForRegularPeriodicPacket({susData.getSid(), false, 5.0}); return returnvalue::OK; } diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index 054f2b8f..fa4ba88e 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -33,13 +33,13 @@ class AcsController : public ExtendedControllerBase { void performPointingCtrl(); private: - /*AcsParameters acsParameters; + AcsParameters acsParameters; SensorProcessing sensorProcessing; Navigation navigation; ActuatorCmd actuatorCmd; Detumble detumble; - uint8_t detumbleCounter;*/ + uint8_t detumbleCounter; enum class InternalState { STARTUP, INITIAL_DELAY, READY }; -- 2.34.1 From 3079dabc20b609a442ea685d803ca6e48a69ed2a Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 6 Oct 2022 15:38:23 +0200 Subject: [PATCH 039/101] combined SensorProcessing and SusConverter --- mission/controller/acs/SensorProcessing.cpp | 737 +++++++++++--------- mission/controller/acs/SensorProcessing.h | 104 ++- mission/controller/acs/SusConverter.cpp | 340 +++------ mission/controller/acs/SusConverter.h | 69 +- 4 files changed, 582 insertions(+), 668 deletions(-) diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index 61f8092b..933800e2 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -6,382 +6,441 @@ */ #include "SensorProcessing.h" -#include "Igrf13Model.h" -#include "util/MathOperations.h" -#include + #include #include #include #include #include +#include + +#include "../controllerdefinitions/AcsCtrlDefinitions.h" +#include "Igrf13Model.h" +#include "util/MathOperations.h" using namespace Math; // Thought: Maybe separate file for transforming of sensor values // into geometry frame and body frame -SensorProcessing::SensorProcessing(AcsParameters *acsParameters_) : - savedMagFieldEst { 0, 0, 0 }{ - validMagField = false; - validGcLatitude = false; +SensorProcessing::SensorProcessing(AcsParameters *acsParameters_) : savedMagFieldEst{0, 0, 0} { + validMagField = false; + validGcLatitude = false; } -SensorProcessing::~SensorProcessing() { +SensorProcessing::~SensorProcessing() {} + +bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const float *mgm1Value, + bool mgm1valid, const float *mgm2Value, bool mgm2valid, + const float *mgm3Value, bool mgm3valid, const float *mgm4Value, + bool mgm4valid, timeval timeOfMgmMeasurement, + const AcsParameters::MgmHandlingParameters *mgmParameters, + const double gpsLatitude, const double gpsLongitude, + const double gpsAltitude, bool gpsValid, double *magFieldEst, + bool *outputValid, double *magFieldModel, + bool *magFieldModelValid, double *magneticFieldVectorDerivative, + bool *magneticFieldVectorDerivativeValid) { + if (!mgm0valid && !mgm1valid && !mgm2valid && !mgm3valid && !mgm4valid) { + *outputValid = false; + validMagField = false; + return false; + } + // Transforming Values to the Body Frame (actually it is the geometry frame atm) + float mgm0ValueBody[3] = {0, 0, 0}, mgm1ValueBody[3] = {0, 0, 0}, mgm2ValueBody[3] = {0, 0, 0}, + mgm3ValueBody[3] = {0, 0, 0}, mgm4ValueBody[3] = {0, 0, 0}; + + bool validUnit[5] = {false, false, false, false, false}; + uint8_t validCount = 0; + if (mgm0valid) { + MatrixOperations::multiply(mgmParameters->mgm0orientationMatrix[0], mgm0Value, + mgm0ValueBody, 3, 3, 1); + validCount += 1; + validUnit[0] = true; + } + if (mgm1valid) { + MatrixOperations::multiply(mgmParameters->mgm1orientationMatrix[0], mgm1Value, + mgm1ValueBody, 3, 3, 1); + validCount += 1; + validUnit[1] = true; + } + if (mgm2valid) { + MatrixOperations::multiply(mgmParameters->mgm2orientationMatrix[0], mgm2Value, + mgm2ValueBody, 3, 3, 1); + validCount += 1; + validUnit[2] = true; + } + if (mgm3valid) { + MatrixOperations::multiply(mgmParameters->mgm3orientationMatrix[0], mgm3Value, + mgm3ValueBody, 3, 3, 1); + validCount += 1; + validUnit[3] = true; + } + if (mgm4valid) { + MatrixOperations::multiply(mgmParameters->mgm4orientationMatrix[0], mgm4Value, + mgm4ValueBody, 3, 3, 1); + validCount += 1; + validUnit[4] = true; + } + + /* -------- MagFieldEst: Middle Value ------- */ + float mgmValues[3][5] = { + {mgm0ValueBody[0], mgm1ValueBody[0], mgm2ValueBody[0], mgm3ValueBody[0], mgm4ValueBody[0]}, + {mgm0ValueBody[1], mgm1ValueBody[1], mgm2ValueBody[1], mgm3ValueBody[1], mgm4ValueBody[1]}, + {mgm0ValueBody[2], mgm1ValueBody[2], mgm2ValueBody[2], mgm3ValueBody[2], mgm4ValueBody[2]}}; + double mgmValidValues[3][validCount]; + uint8_t j = 0; + for (uint8_t i = 0; i < validCount; i++) { + if (validUnit[i]) { + mgmValidValues[0][j] = mgmValues[0][i]; + mgmValidValues[1][j] = mgmValues[1][i]; + mgmValidValues[2][j] = mgmValues[2][i]; + j += 1; + } + } + // Selection Sort + double mgmValidValuesSort[3][validCount]; + MathOperations::selectionSort(*mgmValidValues, *mgmValidValuesSort, 3, validCount); + + uint8_t n = ceil(validCount / 2); + magFieldEst[0] = mgmValidValuesSort[0][n]; + magFieldEst[1] = mgmValidValuesSort[1][n]; + magFieldEst[2] = mgmValidValuesSort[2][n]; + validMagField = true; + + //-----------------------Mag Rate Computation --------------------------------------------------- + double timeDiff = timevalOperations::toDouble(timeOfMgmMeasurement - timeOfSavedMagFieldEst); + for (uint8_t i = 0; i < 3; i++) { + magneticFieldVectorDerivative[i] = (magFieldEst[i] - savedMagFieldEst[i]) / timeDiff; + savedMagFieldEst[i] = magFieldEst[i]; + } + + *magneticFieldVectorDerivativeValid = true; + if (timeOfSavedMagFieldEst.tv_sec == 0) { + magneticFieldVectorDerivative[0] = 0; + magneticFieldVectorDerivative[1] = 0; + magneticFieldVectorDerivative[2] = 0; + *magneticFieldVectorDerivativeValid = false; + } + + timeOfSavedMagFieldEst = timeOfMgmMeasurement; + + *outputValid = true; + + // ---------------- IGRF- 13 Implementation here ------------------------------------------------ + if (!gpsValid) { + *magFieldModelValid = false; + } else { + // Should be existing class object which will be called and modified here. + Igrf13Model igrf13; + // So the line above should not be done here. Update: Can be done here as long updated coffs + // stored in acsParameters ? + igrf13.updateCoeffGH(timeOfMgmMeasurement); + // maybe put a condition here, to only update after a full day, this + // class function has around 700 steps to perform + igrf13.magFieldComp(gpsLongitude, gpsLatitude, gpsAltitude, timeOfMgmMeasurement, + magFieldModel); + *magFieldModelValid = false; + } + + return true; } -bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, - const float *mgm1Value, bool mgm1valid, const float *mgm2Value, - bool mgm2valid, const float *mgm3Value, bool mgm3valid, - const float *mgm4Value, bool mgm4valid, timeval timeOfMgmMeasurement, - const AcsParameters::MgmHandlingParameters *mgmParameters, - const double gpsLatitude, const double gpsLongitude, - const double gpsAltitude, bool gpsValid, double *magFieldEst, bool *outputValid, - double *magFieldModel, bool*magFieldModelValid, - double *magneticFieldVectorDerivative, bool *magneticFieldVectorDerivativeValid) { +void SensorProcessing::processSus(acsctrl::SusDataRaw susData, timeval timeOfSusMeasurement, + const AcsParameters::SusHandlingParameters *susParameters, + const AcsParameters::SunModelParameters *sunModelParameters, + double *sunDirEst, bool *sunDirEstValid, + double *sunVectorInertial, bool *sunVectorInertialValid, + double *sunVectorDerivative, bool *sunVectorDerivativeValid) { + susData.sus0.setValid(susConverter.checkSunSensorData(susData.sus0)); + susData.sus1.setValid(susConverter.checkSunSensorData(susData.sus1)); + susData.sus2.setValid(susConverter.checkSunSensorData(susData.sus2)); + susData.sus3.setValid(susConverter.checkSunSensorData(susData.sus3)); + susData.sus4.setValid(susConverter.checkSunSensorData(susData.sus4)); + susData.sus5.setValid(susConverter.checkSunSensorData(susData.sus5)); + susData.sus6.setValid(susConverter.checkSunSensorData(susData.sus6)); + susData.sus7.setValid(susConverter.checkSunSensorData(susData.sus7)); + susData.sus8.setValid(susConverter.checkSunSensorData(susData.sus8)); + susData.sus9.setValid(susConverter.checkSunSensorData(susData.sus9)); + susData.sus10.setValid(susConverter.checkSunSensorData(susData.sus10)); + susData.sus11.setValid(susConverter.checkSunSensorData(susData.sus11)); - if (!mgm0valid && !mgm1valid && !mgm2valid && !mgm3valid && !mgm4valid) { - *outputValid = false; - validMagField = false; - return false; - } - // Transforming Values to the Body Frame (actually it is the geometry frame atm) - float mgm0ValueBody[3] = {0,0,0}, mgm1ValueBody[3] = {0,0,0}, - mgm2ValueBody[3] = {0,0,0}, mgm3ValueBody[3] = {0,0,0}, - mgm4ValueBody[3] = {0,0,0}; + if (!susData.sus0.isValid() && !susData.sus1.isValid() && !susData.sus2.isValid() && + !susData.sus3.isValid() && !susData.sus4.isValid() && !susData.sus5.isValid() && + !susData.sus6.isValid() && !susData.sus7.isValid() && !susData.sus8.isValid() && + !susData.sus9.isValid() && !susData.sus10.isValid() && !susData.sus11.isValid()) { + *sunDirEstValid = false; + return; + } else { + // WARNING: NOT TRANSFORMED IN BODY FRAME YET + // Transformation into Geomtry Frame + float sus0VecBody[3] = {0, 0, 0}, sus1VecBody[3] = {0, 0, 0}, sus2VecBody[3] = {0, 0, 0}, + sus3VecBody[3] = {0, 0, 0}, sus4VecBody[3] = {0, 0, 0}, sus5VecBody[3] = {0, 0, 0}, + sus6VecBody[3] = {0, 0, 0}, sus7VecBody[3] = {0, 0, 0}, sus8VecBody[3] = {0, 0, 0}, + sus9VecBody[3] = {0, 0, 0}, sus10VecBody[3] = {0, 0, 0}, sus11VecBody[3] = {0, 0, 0}; - bool validUnit[5] = {false, false, false, false, false}; - uint8_t validCount = 0; - if (mgm0valid) { - MatrixOperations::multiply(mgmParameters->mgm0orientationMatrix[0], mgm0Value, mgm0ValueBody, 3, 3, 1); - validCount += 1; - validUnit[0] = true; - } - if (mgm1valid) { - MatrixOperations::multiply(mgmParameters->mgm1orientationMatrix[0], mgm1Value, mgm1ValueBody, 3, 3, 1); - validCount += 1; - validUnit[1] = true; - } - if (mgm2valid) { - MatrixOperations::multiply(mgmParameters->mgm2orientationMatrix[0], mgm2Value, mgm2ValueBody, 3, 3, 1); - validCount += 1; - validUnit[2] = true; - } - if (mgm3valid) { - MatrixOperations::multiply(mgmParameters->mgm3orientationMatrix[0], mgm3Value, mgm3ValueBody, 3, 3, 1); - validCount += 1; - validUnit[3] = true; - } - if (mgm4valid) { - MatrixOperations::multiply(mgmParameters->mgm4orientationMatrix[0], mgm4Value, mgm4ValueBody, 3, 3, 1); - validCount += 1; - validUnit[4] = true; - } + if (susData.sus0.isValid()) { + MatrixOperations::multiply( + susParameters->sus0orientationMatrix[0], + susConverter.getSunVectorSensorFrame(susData.sus0, susParameters->sus0coeffAlpha, + susParameters->sus0coeffBeta), + sus0VecBody, 3, 3, 1); + } + if (susData.sus1.isValid()) { + MatrixOperations::multiply( + susParameters->sus1orientationMatrix[0], + susConverter.getSunVectorSensorFrame(susData.sus1, susParameters->sus1coeffAlpha, + susParameters->sus1coeffBeta), + sus1VecBody, 3, 3, 1); + } + if (susData.sus2.isValid()) { + MatrixOperations::multiply( + susParameters->sus2orientationMatrix[0], + susConverter.getSunVectorSensorFrame(susData.sus2, susParameters->sus2coeffAlpha, + susParameters->sus2coeffBeta), + sus2VecBody, 3, 3, 1); + } + if (susData.sus3.isValid()) { + MatrixOperations::multiply( + susParameters->sus3orientationMatrix[0], + susConverter.getSunVectorSensorFrame(susData.sus3, susParameters->sus3coeffAlpha, + susParameters->sus3coeffBeta), + sus3VecBody, 3, 3, 1); + } + if (susData.sus4.isValid()) { + MatrixOperations::multiply( + susParameters->sus4orientationMatrix[0], + susConverter.getSunVectorSensorFrame(susData.sus4, susParameters->sus4coeffAlpha, + susParameters->sus4coeffBeta), + sus4VecBody, 3, 3, 1); + } + if (susData.sus5.isValid()) { + MatrixOperations::multiply( + susParameters->sus5orientationMatrix[0], + susConverter.getSunVectorSensorFrame(susData.sus5, susParameters->sus5coeffAlpha, + susParameters->sus5coeffBeta), + sus5VecBody, 3, 3, 1); + } + if (susData.sus6.isValid()) { + MatrixOperations::multiply( + susParameters->sus6orientationMatrix[0], + susConverter.getSunVectorSensorFrame(susData.sus6, susParameters->sus6coeffAlpha, + susParameters->sus6coeffBeta), + sus6VecBody, 3, 3, 1); + } + if (susData.sus7.isValid()) { + MatrixOperations::multiply( + susParameters->sus7orientationMatrix[0], + susConverter.getSunVectorSensorFrame(susData.sus7, susParameters->sus7coeffAlpha, + susParameters->sus7coeffBeta), + sus7VecBody, 3, 3, 1); + } + if (susData.sus8.isValid()) { + MatrixOperations::multiply( + susParameters->sus8orientationMatrix[0], + susConverter.getSunVectorSensorFrame(susData.sus8, susParameters->sus8coeffAlpha, + susParameters->sus8coeffBeta), + sus8VecBody, 3, 3, 1); + } + if (susData.sus9.isValid()) { + MatrixOperations::multiply( + susParameters->sus9orientationMatrix[0], + susConverter.getSunVectorSensorFrame(susData.sus9, susParameters->sus9coeffAlpha, + susParameters->sus9coeffBeta), + sus9VecBody, 3, 3, 1); + } + if (susData.sus10.isValid()) { + MatrixOperations::multiply( + susParameters->sus10orientationMatrix[0], + susConverter.getSunVectorSensorFrame(susData.sus10, susParameters->sus10coeffAlpha, + susParameters->sus10coeffBeta), + sus10VecBody, 3, 3, 1); + } + if (susData.sus11.isValid()) { + MatrixOperations::multiply( + susParameters->sus11orientationMatrix[0], + susConverter.getSunVectorSensorFrame(susData.sus11, susParameters->sus11coeffAlpha, + susParameters->sus11coeffBeta), + sus11VecBody, 3, 3, 1); + } - /* -------- MagFieldEst: Middle Value ------- */ - float mgmValues[3][5] = { { mgm0ValueBody[0], mgm1ValueBody[0], mgm2ValueBody[0], - mgm3ValueBody[0], mgm4ValueBody[0] }, { mgm0ValueBody[1], mgm1ValueBody[1], - mgm2ValueBody[1], mgm3ValueBody[1], mgm4ValueBody[1] }, { mgm0ValueBody[2], - mgm1ValueBody[2], mgm2ValueBody[2], mgm3ValueBody[2], mgm4ValueBody[2] } }; - double mgmValidValues[3][validCount]; - uint8_t j = 0; - for (uint8_t i = 0; i < validCount; i++) { - if (validUnit[i]) { - mgmValidValues[0][j] = mgmValues[0][i]; - mgmValidValues[1][j] = mgmValues[1][i]; - mgmValidValues[2][j] = mgmValues[2][i]; - j += 1; - } - } - //Selection Sort - double mgmValidValuesSort[3][validCount]; - MathOperations::selectionSort(*mgmValidValues, *mgmValidValuesSort, 3, validCount); + /* ------ Mean Value: susDirEst ------ */ + // Timo already done + bool validIds[12] = {susData.sus0.isValid(), susData.sus1.isValid(), susData.sus2.isValid(), + susData.sus3.isValid(), susData.sus4.isValid(), susData.sus5.isValid(), + susData.sus6.isValid(), susData.sus7.isValid(), susData.sus8.isValid(), + susData.sus9.isValid(), susData.sus10.isValid(), susData.sus11.isValid()}; + float susVecBody[3][12] = {{sus0VecBody[0], sus1VecBody[0], sus2VecBody[0], sus3VecBody[0], + sus4VecBody[0], sus5VecBody[0], sus6VecBody[0], sus7VecBody[0], + sus8VecBody[0], sus9VecBody[0], sus10VecBody[0], sus11VecBody[0]}, + {sus0VecBody[1], sus1VecBody[1], sus2VecBody[1], sus3VecBody[1], + sus4VecBody[1], sus5VecBody[1], sus6VecBody[1], sus7VecBody[1], + sus8VecBody[1], sus9VecBody[1], sus10VecBody[1], sus11VecBody[1]}, + {sus0VecBody[2], sus1VecBody[2], sus2VecBody[2], sus3VecBody[2], + sus4VecBody[2], sus5VecBody[2], sus6VecBody[2], sus7VecBody[2], + sus8VecBody[2], sus9VecBody[2], sus10VecBody[2], sus11VecBody[2]}}; - uint8_t n = ceil(validCount/2); - magFieldEst[0] = mgmValidValuesSort[0][n]; - magFieldEst[1] = mgmValidValuesSort[1][n]; - magFieldEst[2] = mgmValidValuesSort[2][n]; - validMagField = true; + double susMeanValue[3] = {0, 0, 0}; + uint8_t validSusCounter = 0; + for (uint8_t i = 0; i < 12; i++) { + if (validIds[i]) { + susMeanValue[0] += susVecBody[0][i]; + susMeanValue[1] += susVecBody[1][i]; + susMeanValue[2] += susVecBody[2][i]; + validSusCounter += 1; + } + } + double divisor = 1 / validSusCounter; + VectorOperations::mulScalar(susMeanValue, divisor, sunDirEst, 3); + *sunDirEstValid = true; + } - //-----------------------Mag Rate Computation --------------------------------------------------- - double timeDiff = timevalOperations::toDouble(timeOfMgmMeasurement - timeOfSavedMagFieldEst); - for (uint8_t i = 0; i < 3; i++) { - magneticFieldVectorDerivative[i] = (magFieldEst[i] - - savedMagFieldEst[i]) / timeDiff; - savedMagFieldEst[i] = magFieldEst[i]; - } + /* -------- Sun Derivatiative --------------------- */ - *magneticFieldVectorDerivativeValid = true; - if (timeOfSavedMagFieldEst.tv_sec == 0) { - magneticFieldVectorDerivative[0] = 0; - magneticFieldVectorDerivative[1] = 0; - magneticFieldVectorDerivative[2] = 0; - *magneticFieldVectorDerivativeValid = false; - } + double timeDiff = timevalOperations::toDouble(timeOfSusMeasurement - timeOfSavedSusDirEst); + for (uint8_t i = 0; i < 3; i++) { + sunVectorDerivative[i] = (sunDirEst[i] - savedSunVector[i]) / timeDiff; + savedSunVector[i] = sunDirEst[i]; + } - timeOfSavedMagFieldEst = timeOfMgmMeasurement; + *sunVectorDerivativeValid = true; + if (timeOfSavedSusDirEst.tv_sec == 0) { + sunVectorDerivative[0] = 0; + sunVectorDerivative[1] = 0; + sunVectorDerivative[2] = 0; + *sunVectorDerivativeValid = false; + } + timeOfSavedSusDirEst = timeOfSusMeasurement; - *outputValid = true; + /* -------- Sun Model Direction (IJK frame) ------- */ + // if (useSunModel) eventuell + double JD2000 = MathOperations::convertUnixToJD2000(timeOfSusMeasurement); - // ---------------- IGRF- 13 Implementation here ------------------------------------------------ - if (!gpsValid){ - *magFieldModelValid = false; - } - else{ - // Should be existing class object which will be called and modified here. - Igrf13Model igrf13; - // So the line above should not be done here. Update: Can be done here as long updated coffs -// stored in acsParameters ? - igrf13.updateCoeffGH(timeOfMgmMeasurement); - // maybe put a condition here, to only update after a full day, this - // class function has around 700 steps to perform - igrf13.magFieldComp(gpsLongitude, gpsLatitude, gpsAltitude, - timeOfMgmMeasurement, magFieldModel); - *magFieldModelValid = false; - } + // Julean Centuries + double JC2000 = JD2000 / 36525; - return true; + double meanLongitude = + (sunModelParameters->omega_0 + (sunModelParameters->domega) * JC2000) * PI / 180; + double meanAnomaly = (sunModelParameters->m_0 + sunModelParameters->dm * JC2000) * PI / 180.; + + double eclipticLongitude = meanLongitude + sunModelParameters->p1 * sin(meanAnomaly) + + sunModelParameters->p2 * sin(2 * meanAnomaly); + + double epsilon = sunModelParameters->e - (sunModelParameters->e1) * JC2000; + + sunVectorInertial[0] = cos(eclipticLongitude); + sunVectorInertial[1] = sin(eclipticLongitude) * cos(epsilon); + sunVectorInertial[2] = sin(eclipticLongitude) * sin(epsilon); + + *sunVectorInertialValid = true; } -void SensorProcessing::processSus(const float sus0Value[], bool sus0valid, const float sus1Value[], bool sus1valid, - const float sus2Value[], bool sus2valid, const float sus3Value[], bool sus3valid, - const float sus4Value[], bool sus4valid, const float sus5Value[], bool sus5valid, - const float sus6Value[], bool sus6valid, const float sus7Value[], bool sus7valid, - const float sus8Value[], bool sus8valid, const float sus9Value[], bool sus9valid, - const float sus10Value[], bool sus10valid, const float sus11Value[], bool sus11valid, - timeval timeOfSusMeasurement, const AcsParameters::SusHandlingParameters *susParameters, - const AcsParameters::SunModelParameters *sunModelParameters, double *sunDirEst, bool *sunDirEstValid, - double *sunVectorInertial, bool *sunVectorInertialValid, - double *sunVectorDerivative, bool *sunVectorDerivativeValid){ - - if(!sus0valid && !sus1valid && !sus2valid && !sus3valid && !sus4valid && !sus5valid - && !sus6valid && !sus7valid && !sus8valid && !sus9valid && !sus10valid && !sus11valid){ - *sunDirEstValid = false; - return; - } - else{ - // WARNING: NOT TRANSFORMED IN BODY FRAME YET - // Transformation into Geomtry Frame - float sus0ValueBody[3] = {0,0,0}, sus1ValueBody[3] = {0,0,0}, sus2ValueBody[3] = {0,0,0}, - sus3ValueBody[3] = {0,0,0}, sus4ValueBody[3] = {0,0,0}, sus5ValueBody[3] = {0,0,0}, - sus6ValueBody[3] = {0,0,0}, sus7ValueBody[3] = {0,0,0}, sus8ValueBody[3] = {0,0,0}, - sus9ValueBody[3] = {0,0,0}, sus10ValueBody[3] = {0,0,0}, sus11ValueBody[3] = {0,0,0}; - - if (sus0valid) { - MatrixOperations::multiply(susParameters->sus0orientationMatrix[0], sus0Value, sus0ValueBody, 3, 3, 1); - } - if (sus1valid) { - MatrixOperations::multiply(susParameters->sus1orientationMatrix[0], sus1Value, sus1ValueBody, 3, 3, 1); - } - if (sus2valid) { - MatrixOperations::multiply(susParameters->sus2orientationMatrix[0], sus2Value, sus2ValueBody, 3, 3, 1); - } - if (sus3valid) { - MatrixOperations::multiply(susParameters->sus3orientationMatrix[0], sus3Value, sus3ValueBody, 3, 3, 1); - } - if (sus4valid) { - MatrixOperations::multiply(susParameters->sus4orientationMatrix[0], sus4Value, sus4ValueBody, 3, 3, 1); - } - if (sus5valid) { - MatrixOperations::multiply(susParameters->sus5orientationMatrix[0], sus5Value, sus5ValueBody, 3, 3, 1); - } - if (sus6valid) { - MatrixOperations::multiply(susParameters->sus6orientationMatrix[0], sus6Value, sus6ValueBody, 3, 3, 1); - } - if (sus7valid) { - MatrixOperations::multiply(susParameters->sus7orientationMatrix[0], sus7Value, sus7ValueBody, 3, 3, 1); - } - if (sus8valid) { - MatrixOperations::multiply(susParameters->sus8orientationMatrix[0], sus8Value, sus8ValueBody, 3, 3, 1); - } - if (sus9valid) { - MatrixOperations::multiply(susParameters->sus9orientationMatrix[0], sus9Value, sus9ValueBody, 3, 3, 1); - } - if (sus10valid) { - MatrixOperations::multiply(susParameters->sus10orientationMatrix[0], sus10Value, sus10ValueBody, 3, 3, 1); - } - if (sus11valid) { - MatrixOperations::multiply(susParameters->sus11orientationMatrix[0], sus11Value, sus11ValueBody, 3, 3, 1); - } - - /* ------ Mean Value: susDirEst ------ */ - // Timo already done - bool validIds[12] = {sus0valid, sus1valid, sus2valid, sus3valid, sus4valid, sus5valid, - sus6valid, sus7valid, sus8valid, sus9valid, sus10valid, sus11valid}; - float susValuesBody[3][12] = {{sus0ValueBody[0], sus1ValueBody[0], sus2ValueBody[0], sus3ValueBody[0], sus4ValueBody[0], - sus5ValueBody[0], sus6ValueBody[0], sus7ValueBody[0], sus8ValueBody[0], sus9ValueBody[0], sus10ValueBody[0], sus11ValueBody[0]}, - {sus0ValueBody[1], sus1ValueBody[1], sus2ValueBody[1], sus3ValueBody[1], sus4ValueBody[1], - sus5ValueBody[1], sus6ValueBody[1], sus7ValueBody[1], sus8ValueBody[1], sus9ValueBody[1], sus10ValueBody[1], sus11ValueBody[1]}, - {sus0ValueBody[2], sus1ValueBody[2], sus2ValueBody[2], sus3ValueBody[2], sus4ValueBody[2], - sus5ValueBody[2], sus6ValueBody[2], sus7ValueBody[2], sus8ValueBody[2], sus9ValueBody[2], sus10ValueBody[2], sus11ValueBody[2]}}; - - double susMeanValue[3] = {0,0,0}; - uint8_t validSusCounter = 0; - for (uint8_t i = 0; i < 12; i++){ - if (validIds[i]){ - susMeanValue[0]+=susValuesBody[0][i]; - susMeanValue[1]+=susValuesBody[1][i]; - susMeanValue[2]+=susValuesBody[2][i]; - validSusCounter+=1; - } - } - double divisor = 1/validSusCounter; - VectorOperations::mulScalar(susMeanValue, divisor, sunDirEst, 3); - *sunDirEstValid = true; - } - - /* -------- Sun Derivatiative --------------------- */ - - double timeDiff = timevalOperations::toDouble(timeOfSusMeasurement - timeOfSavedSusDirEst); - for (uint8_t i = 0; i < 3; i++) { - sunVectorDerivative[i] = (sunDirEst[i] - - savedSunVector[i]) / timeDiff; - savedSunVector[i] = sunDirEst[i]; - } - - *sunVectorDerivativeValid = true; - if (timeOfSavedSusDirEst.tv_sec == 0) { - sunVectorDerivative[0] = 0; - sunVectorDerivative[1] = 0; - sunVectorDerivative[2] = 0; - *sunVectorDerivativeValid = false; - } - - timeOfSavedSusDirEst = timeOfSusMeasurement; - - /* -------- Sun Model Direction (IJK frame) ------- */ - // if (useSunModel) eventuell - double JD2000 = MathOperations::convertUnixToJD2000(timeOfSusMeasurement); - - //Julean Centuries - double JC2000 = JD2000 / 36525; - - double meanLongitude = (sunModelParameters->omega_0 + (sunModelParameters->domega) * JC2000) * PI /180; - double meanAnomaly = (sunModelParameters->m_0 - + sunModelParameters->dm * JC2000) * PI / 180.; - - double eclipticLongitude = meanLongitude + sunModelParameters->p1 * sin(meanAnomaly) - + sunModelParameters->p2 * sin(2 * meanAnomaly); - - double epsilon = sunModelParameters->e - (sunModelParameters->e1) * JC2000; - - - sunVectorInertial[0] = cos(eclipticLongitude); - sunVectorInertial[1] = sin(eclipticLongitude) - * cos(epsilon); - sunVectorInertial[2] = sin(eclipticLongitude) - * sin(epsilon); - - - *sunVectorInertialValid = true; -} - - void SensorProcessing::processRmu(const double rmu0Value[], bool rmu0valid, - const double rmu1Value[], bool rmu1valid, - const double rmu2Value[], bool rmu2valid, - timeval timeOfrmuMeasurement, const AcsParameters::RmuHandlingParameters *rmuParameters, - double *satRatEst, bool *satRateEstValid){ + const double rmu1Value[], bool rmu1valid, + const double rmu2Value[], bool rmu2valid, + timeval timeOfrmuMeasurement, + const AcsParameters::RmuHandlingParameters *rmuParameters, + double *satRatEst, bool *satRateEstValid) { + if (!rmu0valid && !rmu1valid && !rmu2valid) { + *satRateEstValid = false; + return; + } + // Transforming Values to the Body Frame (actually it is the geometry frame atm) + double rmu0ValueBody[3] = {0, 0, 0}, rmu1ValueBody[3] = {0, 0, 0}, rmu2ValueBody[3] = {0, 0, 0}; - if (!rmu0valid && !rmu1valid && !rmu2valid) { - *satRateEstValid = false; - return; - } - // Transforming Values to the Body Frame (actually it is the geometry frame atm) - double rmu0ValueBody[3] = {0,0,0}, rmu1ValueBody[3]= {0,0,0}, - rmu2ValueBody[3] = {0,0,0}; + bool validUnit[3] = {false, false, false}; + uint8_t validCount = 0; + if (rmu0valid) { + MatrixOperations::multiply(rmuParameters->rmu0orientationMatrix[0], rmu0Value, + rmu0ValueBody, 3, 3, 1); + validCount += 1; + validUnit[0] = true; + } + if (rmu1valid) { + MatrixOperations::multiply(rmuParameters->rmu1orientationMatrix[0], rmu1Value, + rmu1ValueBody, 3, 3, 1); + validCount += 1; + validUnit[1] = true; + } + if (rmu2valid) { + MatrixOperations::multiply(rmuParameters->rmu2orientationMatrix[0], rmu2Value, + rmu2ValueBody, 3, 3, 1); + validCount += 1; + validUnit[2] = true; + } - bool validUnit[3] = {false, false, false}; - uint8_t validCount = 0; - if (rmu0valid) { - MatrixOperations::multiply(rmuParameters->rmu0orientationMatrix[0], rmu0Value, rmu0ValueBody, 3, 3, 1); - validCount += 1; - validUnit[0] = true; - } - if (rmu1valid) { - MatrixOperations::multiply(rmuParameters->rmu1orientationMatrix[0], rmu1Value, rmu1ValueBody, 3, 3, 1); - validCount += 1; - validUnit[1] = true; - } - if (rmu2valid) { - MatrixOperations::multiply(rmuParameters->rmu2orientationMatrix[0], rmu2Value, rmu2ValueBody, 3, 3, 1); - validCount += 1; - validUnit[2] = true; - } - - /* -------- SatRateEst: Middle Value ------- */ - double rmuValues[3][3] = { { rmu0ValueBody[0], rmu1ValueBody[0], rmu2ValueBody[0]}, { rmu0ValueBody[1], rmu1ValueBody[1], - rmu2ValueBody[1]}, { rmu0ValueBody[2], - rmu1ValueBody[2], rmu2ValueBody[2]} }; - double rmuValidValues[3][validCount]; - uint8_t j = 0; - for (uint8_t i = 0; i < validCount; i++) { - if (validUnit[i]) { - rmuValidValues[0][j] = rmuValues[0][i]; - rmuValidValues[1][j] = rmuValues[1][i]; - rmuValidValues[2][j] = rmuValues[2][i]; - j += 1; - } - } - //Selection Sort - double rmuValidValuesSort[3][validCount]; - MathOperations::selectionSort(*rmuValidValues, *rmuValidValuesSort, 3, validCount); - - uint8_t n = ceil(validCount/2); - satRatEst[0] = rmuValidValuesSort[0][n]; - satRatEst[1] = rmuValidValuesSort[1][n]; - satRatEst[2] = rmuValidValuesSort[2][n]; - *satRateEstValid = true; + /* -------- SatRateEst: Middle Value ------- */ + double rmuValues[3][3] = {{rmu0ValueBody[0], rmu1ValueBody[0], rmu2ValueBody[0]}, + {rmu0ValueBody[1], rmu1ValueBody[1], rmu2ValueBody[1]}, + {rmu0ValueBody[2], rmu1ValueBody[2], rmu2ValueBody[2]}}; + double rmuValidValues[3][validCount]; + uint8_t j = 0; + for (uint8_t i = 0; i < validCount; i++) { + if (validUnit[i]) { + rmuValidValues[0][j] = rmuValues[0][i]; + rmuValidValues[1][j] = rmuValues[1][i]; + rmuValidValues[2][j] = rmuValues[2][i]; + j += 1; + } + } + // Selection Sort + double rmuValidValuesSort[3][validCount]; + MathOperations::selectionSort(*rmuValidValues, *rmuValidValuesSort, 3, validCount); + uint8_t n = ceil(validCount / 2); + satRatEst[0] = rmuValidValuesSort[0][n]; + satRatEst[1] = rmuValidValuesSort[1][n]; + satRatEst[2] = rmuValidValuesSort[2][n]; + *satRateEstValid = true; } void SensorProcessing::processGps(const double gps0latitude, const double gps0longitude, - const bool validGps, double *gcLatitude, double *gdLongitude){ - // name to convert not process - if (validGps) { - // Transforming from Degree to Radians and calculation geocentric lattitude from geodetic - *gdLongitude = gps0longitude * PI / 180; - double latitudeRad = gps0latitude * PI / 180; - double eccentricityWgs84 = 0.0818195; - double factor = 1 - pow(eccentricityWgs84, 2); - *gcLatitude = atan(factor * tan(latitudeRad)); - validGcLatitude = true; - - } + const bool validGps, double *gcLatitude, double *gdLongitude) { + // name to convert not process + if (validGps) { + // Transforming from Degree to Radians and calculation geocentric lattitude from geodetic + *gdLongitude = gps0longitude * PI / 180; + double latitudeRad = gps0latitude * PI / 180; + double eccentricityWgs84 = 0.0818195; + double factor = 1 - pow(eccentricityWgs84, 2); + *gcLatitude = atan(factor * tan(latitudeRad)); + validGcLatitude = true; + } } void SensorProcessing::process(timeval now, ACS::SensorValues *sensorValues, - ACS::OutputValues *outputValues, const AcsParameters *acsParameters) { + ACS::OutputValues *outputValues, + const AcsParameters *acsParameters) { + sensorValues->update(); + processGps(sensorValues->gps0latitude, sensorValues->gps0longitude, sensorValues->gps0Valid, + &outputValues->gcLatitude, &outputValues->gdLongitude); - sensorValues->update(); - processGps(sensorValues->gps0latitude, sensorValues->gps0longitude, - sensorValues->gps0Valid, &outputValues->gcLatitude, &outputValues->gdLongitude); - - outputValues->mgmUpdated = processMgm(sensorValues->mgm0, sensorValues->mgm0Valid, - sensorValues->mgm1, sensorValues->mgm1Valid, - sensorValues->mgm2, sensorValues->mgm2Valid, - sensorValues->mgm3, sensorValues->mgm3Valid, - sensorValues->mgm4, sensorValues->mgm4Valid, now, - &acsParameters->mgmHandlingParameters, outputValues->gcLatitude, - outputValues->gdLongitude, sensorValues->gps0altitude, - sensorValues->gps0Valid, - outputValues->magFieldEst, &outputValues->magFieldEstValid, - outputValues->magFieldModel, &outputValues->magFieldModelValid, - outputValues->magneticFieldVectorDerivative, &outputValues->magneticFieldVectorDerivativeValid); // VALID outputs- PoolVariable ? - - processSus(sensorValues->sus0, sensorValues->sus0Valid, sensorValues->sus1, sensorValues->sus1Valid, - sensorValues->sus2, sensorValues->sus2Valid, sensorValues->sus3, sensorValues->sus3Valid, - sensorValues->sus4, sensorValues->sus4Valid, sensorValues->sus5, sensorValues->sus5Valid, - sensorValues->sus6, sensorValues->sus6Valid, sensorValues->sus7, sensorValues->sus7Valid, - sensorValues->sus8, sensorValues->sus8Valid, sensorValues->sus9, sensorValues->sus9Valid, - sensorValues->sus10, sensorValues->sus10Valid, sensorValues->sus11, sensorValues->sus11Valid, - now, &acsParameters->susHandlingParameters, &acsParameters->sunModelParameters, - outputValues->sunDirEst, &outputValues->sunDirEstValid, - outputValues->sunDirModel, &outputValues->sunDirModelValid, - outputValues->sunVectorDerivative, &outputValues->sunVectorDerivativeValid); // VALID outputs ? - - processRmu(sensorValues->rmu0, sensorValues->rmu0Valid, sensorValues->rmu1, sensorValues->rmu1Valid, - sensorValues->rmu2, sensorValues->rmu2Valid, now, &acsParameters->rmuHandlingParameters, - outputValues->satRateEst, &outputValues->satRateEstValid); + /*outputValues->mgmUpdated = processMgm(sensorValues->mgm0, sensorValues->mgm0Valid, + sensorValues->mgm1, sensorValues->mgm1Valid, + sensorValues->mgm2, sensorValues->mgm2Valid, + sensorValues->mgm3, sensorValues->mgm3Valid, + sensorValues->mgm4, sensorValues->mgm4Valid, now, + &acsParameters->mgmHandlingParameters, outputValues->gcLatitude, + outputValues->gdLongitude, sensorValues->gps0altitude, + sensorValues->gps0Valid, + outputValues->magFieldEst, &outputValues->magFieldEstValid, + outputValues->magFieldModel, &outputValues->magFieldModelValid, + outputValues->magneticFieldVectorDerivative, + &outputValues->magneticFieldVectorDerivativeValid); // VALID outputs- PoolVariable ? + processSus(sensorValues->sus0, sensorValues->sus0Valid, sensorValues->sus1, + sensorValues->sus1Valid, sensorValues->sus2, sensorValues->sus2Valid, sensorValues->sus3, + sensorValues->sus3Valid, sensorValues->sus4, sensorValues->sus4Valid, sensorValues->sus5, + sensorValues->sus5Valid, sensorValues->sus6, sensorValues->sus6Valid, sensorValues->sus7, + sensorValues->sus7Valid, sensorValues->sus8, sensorValues->sus8Valid, sensorValues->sus9, + sensorValues->sus9Valid, sensorValues->sus10, sensorValues->sus10Valid, sensorValues->sus11, + sensorValues->sus11Valid, now, &acsParameters->susHandlingParameters, + &acsParameters->sunModelParameters, outputValues->sunDirEst, &outputValues->sunDirEstValid, + outputValues->sunDirModel, &outputValues->sunDirModelValid, + outputValues->sunVectorDerivative, &outputValues->sunVectorDerivativeValid); // + VALID outputs ? +*/ + processRmu(sensorValues->rmu0, sensorValues->rmu0Valid, sensorValues->rmu1, + sensorValues->rmu1Valid, sensorValues->rmu2, sensorValues->rmu2Valid, now, + &acsParameters->rmuHandlingParameters, outputValues->satRateEst, + &outputValues->satRateEstValid); } - diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h index 097c88ed..baa9c5b6 100644 --- a/mission/controller/acs/SensorProcessing.h +++ b/mission/controller/acs/SensorProcessing.h @@ -5,14 +5,16 @@ #ifndef SENSORPROCESSING_H_ #define SENSORPROCESSING_H_ -#include "AcsParameters.h" -#include "SensorValues.h" -#include "OutputValues.h" -#include "config/classIds.h" -#include //uint8_t -#include /*purpose, timeval ?*/ #include +#include //uint8_t +#include /*purpose, timeval ?*/ +#include "SusConverter.h" +#include "../controllerdefinitions/AcsCtrlDefinitions.h" +#include "AcsParameters.h" +#include "OutputValues.h" +#include "SensorValues.h" +#include "config/classIds.h" /*Planned: * - Fusion of Sensor Measurements - @@ -26,65 +28,53 @@ * magField * SunDirEst*/ -class SensorProcessing{ -public: +class SensorProcessing { + public: + void reset(); - void reset(); + SensorProcessing(AcsParameters *acsParameters_); + virtual ~SensorProcessing(); - SensorProcessing(AcsParameters *acsParameters_); - virtual ~SensorProcessing(); + void process(timeval now, ACS::SensorValues *sensorValues, ACS::OutputValues *outputValues, + const AcsParameters *acsParameters); // Will call protected functions + private: + protected: + // short description needed for every function + bool processMgm(const float *mgm0Value, bool mgm0valid, const float *mgm1Value, bool mgm1valid, + const float *mgm2Value, bool mgm2valid, const float *mgm3Value, bool mgm3valid, + const float *mgm4Value, bool mgm4valid, timeval timeOfMgmMeasurement, + const AcsParameters::MgmHandlingParameters *mgmParameters, + const double gpsLatitude, const double gpsLongitude, const double gpsAltitude, + bool gpsValid, double *magFieldEst, bool *outputValid, double *magFieldModel, + bool *magFieldModelValid, double *magneticFieldVectorDerivative, + bool *magneticFieldVectorDerivativeValid); // Output - void process(timeval now, ACS::SensorValues* sensorValues, ACS::OutputValues *outputValues, - const AcsParameters *acsParameters); // Will call protected functions -private: + void processSus(acsctrl::SusDataRaw susData, timeval timeOfSusMeasurement, + const AcsParameters::SusHandlingParameters *susParameters, + const AcsParameters::SunModelParameters *sunModelParameters, double *sunDirEst, + bool *sunDirEstValid, double *sunVectorInertial, bool *sunVectorInertialValid, + double *sunVectorDerivative, bool *sunVectorDerivativeValid); -protected: - // short description needed for every function - bool processMgm(const float *mgm0Value, bool mgm0valid, - const float *mgm1Value, bool mgm1valid, - const float *mgm2Value, bool mgm2valid, - const float *mgm3Value, bool mgm3valid, - const float *mgm4Value, bool mgm4valid, - timeval timeOfMgmMeasurement, - const AcsParameters::MgmHandlingParameters *mgmParameters, - const double gpsLatitude, const double gpsLongitude, - const double gpsAltitude, bool gpsValid, - double *magFieldEst, bool *outputValid, - double *magFieldModel, bool*magFieldModelValid, - double *magneticFieldVectorDerivative, bool *magneticFieldVectorDerivativeValid); //Output + void processRmu(const double rmu0Value[], bool rmu0valid, // processRmu + const double rmu1Value[], bool rmu1valid, const double rmu2Value[], + bool rmu2valid, timeval timeOfrmuMeasurement, + const AcsParameters::RmuHandlingParameters *rmuParameters, double *satRatEst, + bool *satRateEstValid); - void processSus(const float sus0Value[], bool sus0valid, const float sus1Value[], bool sus1valid, - const float sus2Value[], bool sus2valid, const float sus3Value[], bool sus3valid, - const float sus4Value[], bool sus4valid, const float sus5Value[], bool sus5valid, - const float sus6Value[], bool sus6valid, const float sus7Value[], bool sus7valid, - const float sus8Value[], bool sus8valid, const float sus9Value[], bool sus9valid, - const float sus10Value[], bool sus10valid, const float sus11Value[], bool sus11valid, - timeval timeOfSusMeasurement, const AcsParameters::SusHandlingParameters *susParameters, - const AcsParameters::SunModelParameters *sunModelParameters, double *sunDirEst, bool *sunDirEstValid, - double *sunVectorModel, bool *sunVectorModelValid, - double *sunVectorDerivative, bool *sunVectorDerivativeValid); + void processStr(); - void processRmu(const double rmu0Value[], bool rmu0valid, // processRmu - const double rmu1Value[], bool rmu1valid, - const double rmu2Value[], bool rmu2valid, - timeval timeOfrmuMeasurement, const AcsParameters::RmuHandlingParameters *rmuParameters, - double *satRatEst, bool *satRateEstValid); - - void processStr(); - - void processGps(const double gps0latitude, const double gps0longitude, - const bool validGps, double *gcLatitude, double *gdLongitude); - - - double savedMagFieldEst[3]; - timeval timeOfSavedMagFieldEst; - double savedSunVector[3]; - timeval timeOfSavedSusDirEst; - bool validMagField; - bool validGcLatitude; + void processGps(const double gps0latitude, const double gps0longitude, const bool validGps, + double *gcLatitude, double *gdLongitude); + double savedMagFieldEst[3]; + timeval timeOfSavedMagFieldEst; + double savedSunVector[3]; + timeval timeOfSavedSusDirEst; + bool validMagField; + bool validGcLatitude; + SusConverter susConverter; + AcsParameters acsParameters; }; #endif /*SENSORPROCESSING_H_*/ - diff --git a/mission/controller/acs/SusConverter.cpp b/mission/controller/acs/SusConverter.cpp index 13f23808..7d8f5bd2 100644 --- a/mission/controller/acs/SusConverter.cpp +++ b/mission/controller/acs/SusConverter.cpp @@ -6,191 +6,68 @@ */ #include "SusConverter.h" -#include //for atan2 -#include -#include + #include #include +#include +#include //for atan2 +#include -void SunSensor::checkSunSensorData(uint8_t susNumber) { - uint16_t channelValueSum; - - // Check individual channel values - for (int k = 0; k < 4; k++) { // iteration above all photodiode quarters - - if (susChannelValues[susNumber][k] <= channelValueCheckLow || - susChannelValues[susNumber][k] > channelValueCheckHigh) { // Channel values out of range for 12 bit SUS - // channel measurement range? - validFlag[susNumber] = returnvalue::FAILED; - /*printf( - "The value of channel %i from sun sensor %i is not inside the borders of valid data with " - "a value of %i \n", - k, susNumber, ChannelValue[k]);*/ - } else if (susChannelValues[susNumber][k] > - susChannelValues[susNumber][4]) { // Channel values higher than zero current threshold GNDREF? - validFlag[susNumber] = returnvalue::FAILED; - /*printf( - "The value of channel %i from sun sensor %i is higher than the zero current threshold " - "GNDREF\n", - k, susNumber);*/ - }; +bool SusConverter::checkSunSensorData(lp_vec_t susChannel) { + if (susChannel.value[0] <= susChannelValueCheckLow || + susChannel.value[0] > susChannelValueCheckHigh || + susChannel.value[0] > susChannel.value[GNDREF]) { + return false; + } + if (susChannel.value[1] <= susChannelValueCheckLow || + susChannel.value[1] > susChannelValueCheckHigh || + susChannel.value[1] > susChannel.value[GNDREF]) { + return false; + }; + if (susChannel.value[2] <= susChannelValueCheckLow || + susChannel.value[2] > susChannelValueCheckHigh || + susChannel.value[2] > susChannel.value[GNDREF]) { + return false; + }; + if (susChannel.value[3] <= susChannelValueCheckLow || + susChannel.value[3] > susChannelValueCheckHigh || + susChannel.value[3] > susChannel.value[GNDREF]) { + return false; }; - // check sum of all channel values to check if sun sensor is illuminated by the sun (sum is - // smaller than a treshold --> sun sensor is not illuminated by the sun, but by the moon - // reflection or earth albedo) - channelValueSum = - 4 * susChannelValues[susNumber][4] - (susChannelValues[susNumber][0] + - susChannelValues[susNumber][1] + susChannelValues[susNumber][2] + - susChannelValues[susNumber][3]); - if ((channelValueSum < channelValueSumHigh) && (channelValueSum > channelValueSumLow)) { - validFlag[susNumber] = returnvalue::FAILED; - //printf("Sun sensor %i is not illuminated by the sun\n", susNumber); + susChannelValueSum = 4 * susChannel.value[GNDREF] - (susChannel.value[0] + susChannel.value[1] + + susChannel.value[2] + susChannel.value[3]); + if ((susChannelValueSum < susChannelValueSumHigh) && + (susChannelValueSum > susChannelValueSumLow)) { + return false; }; + return true; } -void SunSensor::calcAngle(uint8_t susNumber) { +void SusConverter::calcAngle(lp_vec_t susChannel) { float xout, yout; float s = 0.03; // s=[mm] gap between diodes uint8_t d = 5; // d=[mm] edge length of the quadratic aperture uint8_t h = 1; // h=[mm] distance between diodes and aperture int ch0, ch1, ch2, ch3; // Substract measurement values from GNDREF zero current threshold - ch0 = susChannelValues[susNumber][4] - susChannelValues[susNumber][0]; - ch1 = susChannelValues[susNumber][4] - susChannelValues[susNumber][1]; - ch2 = susChannelValues[susNumber][4] - susChannelValues[susNumber][2]; - ch3 = susChannelValues[susNumber][4] - susChannelValues[susNumber][3]; + ch0 = susChannel.value[GNDREF] - susChannel.value[0]; + ch1 = susChannel.value[GNDREF] - susChannel.value[1]; + ch2 = susChannel.value[GNDREF] - susChannel.value[2]; + ch3 = susChannel.value[GNDREF] - susChannel.value[3]; // Calculation of x and y xout = ((d - s) / 2) * (ch2 - ch3 - ch0 + ch1) / (ch0 + ch1 + ch2 + ch3); //[mm] yout = ((d - s) / 2) * (ch2 + ch3 - ch0 - ch1) / (ch0 + ch1 + ch2 + ch3); //[mm] // Calculation of the angles - alphaBetaRaw[susNumber][0] = atan2(xout, h) * (180 / M_PI); //[°] - alphaBetaRaw[susNumber][1] = atan2(yout, h) * (180 / M_PI); //[°] + alphaBetaRaw[0] = atan2(xout, h) * (180 / M_PI); //[°] + alphaBetaRaw[1] = atan2(yout, h) * (180 / M_PI); //[°] } -void SunSensor::setCalibrationCoefficients(uint8_t susNumber) { - switch (susNumber) { // search for the correct calibration coefficients for each SUS - - case 0: - for (uint8_t row = 0; row < 9; - row++) { // save the correct coefficients in the right SUS class - for (uint8_t column = 0; column < 10; column++) { - coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus0coeffAlpha[row][column]; - coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus0coeffBeta[row][column]; - } - } - break; - - case 1: - for (uint8_t row = 0; row < 9; row++) { - for (uint8_t column = 0; column < 10; column++) { - coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus1coeffAlpha[row][column]; - coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus1coeffBeta[row][column]; - } - } - break; - - case 2: - for (uint8_t row = 0; row < 9; row++) { - for (uint8_t column = 0; column < 10; column++) { - coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus2coeffAlpha[row][column]; - coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus2coeffBeta[row][column]; - } - } - break; - - case 3: - for (uint8_t row = 0; row < 9; row++) { - for (uint8_t column = 0; column < 10; column++) { - coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus3coeffAlpha[row][column]; - coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus3coeffBeta[row][column]; - } - } - break; - - case 4: - for (uint8_t row = 0; row < 9; row++) { - for (uint8_t column = 0; column < 10; column++) { - coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus4coeffAlpha[row][column]; - coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus4coeffBeta[row][column]; - } - } - break; - - case 5: - for (uint8_t row = 0; row < 9; row++) { - for (uint8_t column = 0; column < 10; column++) { - coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus5coeffAlpha[row][column]; - coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus5coeffBeta[row][column]; - } - } - break; - - case 6: - for (uint8_t row = 0; row < 9; row++) { - for (uint8_t column = 0; column < 10; column++) { - coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus6coeffAlpha[row][column]; - coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus6coeffBeta[row][column]; - } - } - break; - - case 7: - for (uint8_t row = 0; row < 9; row++) { - for (uint8_t column = 0; column < 10; column++) { - coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus7coeffAlpha[row][column]; - coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus7coeffBeta[row][column]; - } - } - break; - - case 8: - for (uint8_t row = 0; row < 9; row++) { - for (uint8_t column = 0; column < 10; column++) { - coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus8coeffAlpha[row][column]; - coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus8coeffBeta[row][column]; - } - } - break; - - case 9: - for (uint8_t row = 0; row < 9; row++) { - for (uint8_t column = 0; column < 10; column++) { - coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus9coeffAlpha[row][column]; - coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus9coeffBeta[row][column]; - } - } - break; - - case 10: - for (uint8_t row = 0; row < 9; row++) { - for (uint8_t column = 0; column < 10; column++) { - coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus10coeffAlpha[row][column]; - coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus10coeffBeta[row][column]; - } - } - break; - - case 11: - for (uint8_t row = 0; row < 9; row++) { - for (uint8_t column = 0; column < 10; column++) { - coeffAlpha[susNumber][row][column] = acsParameters.susHandlingParameters.sus11coeffAlpha[row][column]; - coeffBeta[susNumber][row][column] = acsParameters.susHandlingParameters.sus11coeffBeta[row][column]; - } - } - break; - } -} - -void SunSensor::Calibration(uint8_t susNumber) { - float alpha_m, beta_m, alpha_calibrated, beta_calibrated, k, l; - uint8_t index; - - alpha_m = alphaBetaRaw[susNumber][0]; //[°] - beta_m = alphaBetaRaw[susNumber][1]; //[°] +void SusConverter::calibration(const float coeffAlpha[9][10], const float coeffBeta[9][10]) { + uint8_t index, k, l; // while loop iterates above all calibration cells to use the different calibration functions in // each cell @@ -201,68 +78,62 @@ void SunSensor::Calibration(uint8_t susNumber) { while (l < 3) { l = l + 1; // if-condition to check in which cell the data point has to be - if ((alpha_m > ((completeCellWidth * ((k - 1) / 3)) - halfCellWidth) && - alpha_m < ((completeCellWidth * (k / 3)) - halfCellWidth)) && - (beta_m > ((completeCellWidth * ((l - 1) / 3)) - halfCellWidth) && - beta_m < ((completeCellWidth * (l / 3)) - halfCellWidth))) { + if ((alphaBetaRaw[0] > ((completeCellWidth * ((k - 1) / 3)) - halfCellWidth) && + alphaBetaRaw[0] < ((completeCellWidth * (k / 3)) - halfCellWidth)) && + (alphaBetaRaw[1] > ((completeCellWidth * ((l - 1) / 3)) - halfCellWidth) && + alphaBetaRaw[1] < ((completeCellWidth * (l / 3)) - halfCellWidth))) { index = (3 * (k - 1) + l) - 1; // calculate the index of the datapoint for the right cell - // -> first cell has number 0 - alphaBetaCalibrated[susNumber][0] = - coeffAlpha[susNumber][index][0] + coeffAlpha[susNumber][index][1] * alpha_m + coeffAlpha[susNumber][index][2] * beta_m + - coeffAlpha[susNumber][index][3] * alpha_m * alpha_m + coeffAlpha[susNumber][index][4] * alpha_m * beta_m + - coeffAlpha[susNumber][index][5] * beta_m * beta_m + - coeffAlpha[susNumber][index][6] * alpha_m * alpha_m * alpha_m + - coeffAlpha[susNumber][index][7] * alpha_m * alpha_m * beta_m + - coeffAlpha[susNumber][index][8] * alpha_m * beta_m * beta_m + - coeffAlpha[susNumber][index][9] * beta_m * beta_m * beta_m; //[°] - alphaBetaCalibrated[susNumber][1] = - coeffBeta[susNumber][index][0] + coeffBeta[susNumber][index][1] * alpha_m + - coeffBeta[susNumber][index][2] * beta_m + coeffBeta[susNumber][index][3] * alpha_m * alpha_m + - coeffBeta[susNumber][index][4] * alpha_m * beta_m + - coeffBeta[susNumber][index][5] * beta_m * beta_m + - coeffBeta[susNumber][index][6] * alpha_m * alpha_m * alpha_m + - coeffBeta[susNumber][index][7] * alpha_m * alpha_m * beta_m + - coeffBeta[susNumber][index][8] * alpha_m * beta_m * beta_m + - coeffBeta[susNumber][index][9] * beta_m * beta_m * beta_m; //[°] + alphaBetaCalibrated[0] = + coeffAlpha[index][0] + coeffAlpha[index][1] * alphaBetaRaw[0] + + coeffAlpha[index][2] * alphaBetaRaw[1] + + coeffAlpha[index][3] * alphaBetaRaw[0] * alphaBetaRaw[0] + + coeffAlpha[index][4] * alphaBetaRaw[0] * alphaBetaRaw[1] + + coeffAlpha[index][5] * alphaBetaRaw[1] * alphaBetaRaw[1] + + coeffAlpha[index][6] * alphaBetaRaw[0] * alphaBetaRaw[0] * alphaBetaRaw[0] + + coeffAlpha[index][7] * alphaBetaRaw[0] * alphaBetaRaw[0] * alphaBetaRaw[1] + + coeffAlpha[index][8] * alphaBetaRaw[0] * alphaBetaRaw[1] * alphaBetaRaw[1] + + coeffAlpha[index][9] * alphaBetaRaw[1] * alphaBetaRaw[1] * alphaBetaRaw[1]; //[°] + alphaBetaCalibrated[1] = + coeffBeta[index][0] + coeffBeta[index][1] * alphaBetaRaw[0] + + coeffBeta[index][2] * alphaBetaRaw[1] + + coeffBeta[index][3] * alphaBetaRaw[0] * alphaBetaRaw[0] + + coeffBeta[index][4] * alphaBetaRaw[0] * alphaBetaRaw[1] + + coeffBeta[index][5] * alphaBetaRaw[1] * alphaBetaRaw[1] + + coeffBeta[index][6] * alphaBetaRaw[0] * alphaBetaRaw[0] * alphaBetaRaw[0] + + coeffBeta[index][7] * alphaBetaRaw[0] * alphaBetaRaw[0] * alphaBetaRaw[1] + + coeffBeta[index][8] * alphaBetaRaw[0] * alphaBetaRaw[1] * alphaBetaRaw[1] + + coeffBeta[index][9] * alphaBetaRaw[1] * alphaBetaRaw[1] * alphaBetaRaw[1]; //[°] } } } } -void SunSensor::CalculateSunVector(uint8_t susNumber) { - float alpha, beta; - alpha = alphaBetaCalibrated[susNumber][0]; //[°] - beta = alphaBetaCalibrated[susNumber][1]; //[°] - +float* SusConverter::calculateSunVector() { // Calculate the normalized Sun Vector - sunVectorBodyFrame[susNumber][0] = - (tan(alpha * (M_PI / 180)) / - (sqrt((powf(tan(alpha * (M_PI / 180)), 2)) + powf(tan((beta * (M_PI / 180))), 2) + (1)))); - sunVectorBodyFrame[susNumber][1] = - (tan(beta * (M_PI / 180)) / - (sqrt(powf((tan(alpha * (M_PI / 180))), 2) + powf(tan((beta * (M_PI / 180))), 2) + (1)))); - sunVectorBodyFrame[susNumber][2] = - (-1 / - (sqrt(powf((tan(alpha * (M_PI / 180))), 2) + powf((tan(beta * (M_PI / 180))), 2) + (1)))); + sunVectorBodyFrame[0] = (tan(alphaBetaCalibrated[0] * (M_PI / 180)) / + (sqrt((powf(tan(alphaBetaCalibrated[0] * (M_PI / 180)), 2)) + + powf(tan((alphaBetaCalibrated[1] * (M_PI / 180))), 2) + (1)))); + sunVectorBodyFrame[1] = (tan(alphaBetaCalibrated[1] * (M_PI / 180)) / + (sqrt(powf((tan(alphaBetaCalibrated[0] * (M_PI / 180))), 2) + + powf(tan((alphaBetaCalibrated[1] * (M_PI / 180))), 2) + (1)))); + sunVectorBodyFrame[2] = + (-1 / (sqrt(powf((tan(alphaBetaCalibrated[0] * (M_PI / 180))), 2) + + powf((tan(alphaBetaCalibrated[1] * (M_PI / 180))), 2) + (1)))); + + return sunVectorBodyFrame; } -float* SunSensor::getSunVectorBodyFrame(uint8_t susNumber) { - // return function for the sun vector in the body frame - float* SunVectorBodyFrameReturn = 0; - SunVectorBodyFrameReturn = new float[3]; - - SunVectorBodyFrameReturn[0] = sunVectorBodyFrame[susNumber][0]; - SunVectorBodyFrameReturn[1] = sunVectorBodyFrame[susNumber][1]; - SunVectorBodyFrameReturn[2] = sunVectorBodyFrame[susNumber][2]; - - return SunVectorBodyFrameReturn; +float* SusConverter::getSunVectorSensorFrame(lp_vec_t susChannel, + const float coeffAlpha[9][10], + const float coeffBeta[9][10]) { + calcAngle(susChannel); + calibration(coeffAlpha, coeffBeta); + return calculateSunVector(); } -bool SunSensor::getValidFlag(uint8_t susNumber) { - return validFlag[susNumber]; -} +bool SusConverter::getValidFlag(uint8_t susNumber) { return validFlag[susNumber]; } -float* SunSensor::TransferSunVector() { +float* SusConverter::TransferSunVector() { float* sunVectorEIVE = 0; sunVectorEIVE = new float[3]; @@ -273,7 +144,7 @@ float* SunSensor::TransferSunVector() { for (uint8_t susNumber = 0; susNumber < 12; susNumber++) { // save the sun vector of each SUS in their body frame into an array for - // further processing + // further processing float* SunVectorBodyFrame = &SunVectorBodyFrame[susNumber]; sunVectorMatrixBodyFrame[0][susNumber] = SunVectorBodyFrame[0]; sunVectorMatrixBodyFrame[1][susNumber] = SunVectorBodyFrame[1]; @@ -288,42 +159,53 @@ float* SunSensor::TransferSunVector() { for (uint8_t c1 = 0; c1 < 3; c1++) { for (uint8_t c2 = 0; c2 < 3; c2++) { switch (susNumber) { - case 0: - basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus0orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = + acsParameters.susHandlingParameters.sus0orientationMatrix[c1][c2]; break; case 1: - basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus1orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = + acsParameters.susHandlingParameters.sus1orientationMatrix[c1][c2]; break; case 2: - basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus2orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = + acsParameters.susHandlingParameters.sus2orientationMatrix[c1][c2]; break; case 3: - basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus3orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = + acsParameters.susHandlingParameters.sus3orientationMatrix[c1][c2]; break; case 4: - basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus4orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = + acsParameters.susHandlingParameters.sus4orientationMatrix[c1][c2]; break; case 5: - basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus5orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = + acsParameters.susHandlingParameters.sus5orientationMatrix[c1][c2]; break; case 6: - basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus6orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = + acsParameters.susHandlingParameters.sus6orientationMatrix[c1][c2]; break; case 7: - basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus7orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = + acsParameters.susHandlingParameters.sus7orientationMatrix[c1][c2]; break; case 8: - basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus8orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = + acsParameters.susHandlingParameters.sus8orientationMatrix[c1][c2]; break; case 9: - basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus9orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = + acsParameters.susHandlingParameters.sus9orientationMatrix[c1][c2]; break; case 10: - basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus10orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = + acsParameters.susHandlingParameters.sus10orientationMatrix[c1][c2]; break; case 11: - basisMatrixUse[c1][c2] = acsParameters.susHandlingParameters.sus11orientationMatrix[c1][c2]; + basisMatrixUse[c1][c2] = + acsParameters.susHandlingParameters.sus11orientationMatrix[c1][c2]; break; } } @@ -343,9 +225,9 @@ float* SunSensor::TransferSunVector() { for (uint8_t i = 0; i < 3; i++) { float sum = 0; for (uint8_t susNumber = 0; susNumber < 12; susNumber++) { - if (getValidFlag(susNumber) == returnvalue::OK){ + if (getValidFlag(susNumber) == returnvalue::OK) { sum += sunVectorMatrixEIVE[i][susNumber]; - //printf("%f\n", SunVectorMatrixEIVE[i][susNumber]); + // printf("%f\n", SunVectorMatrixEIVE[i][susNumber]); } } // ToDo: decide on length on sun vector @@ -359,5 +241,3 @@ float* SunSensor::TransferSunVector() { return sunVectorEIVE; } - - diff --git a/mission/controller/acs/SusConverter.h b/mission/controller/acs/SusConverter.h index bfec1dfe..32f9e954 100644 --- a/mission/controller/acs/SusConverter.h +++ b/mission/controller/acs/SusConverter.h @@ -8,69 +8,54 @@ #ifndef MISSION_CONTROLLER_ACS_SUSCONVERTER_H_ #define MISSION_CONTROLLER_ACS_SUSCONVERTER_H_ -#include "AcsParameters.h" +#include #include -class SunSensor { - public: - SunSensor() {} +#include "AcsParameters.h" - void checkSunSensorData(uint8_t susNumber); - void calcAngle(uint8_t susNumber); - void setCalibrationCoefficients(uint8_t susNumber); - void Calibration(uint8_t susNumber); - void CalculateSunVector(uint8_t susNumber); +class SusConverter { + public: + SusConverter() {} + + bool checkSunSensorData(lp_vec_t susChannel); + + void calcAngle(lp_vec_t susChannel); + void calibration(const float coeffAlpha[9][10], const float coeffBeta[9][10]); + float* calculateSunVector(); bool getValidFlag(uint8_t susNumber); - float* getSunVectorBodyFrame(uint8_t susNumber); + float* getSunVectorSensorFrame(lp_vec_t susChannel, const float coeffAlpha[9][10], + const float coeffBeta[9][10]); float* TransferSunVector(); private: - // ToDo: remove statics and replace with actual data - uint16_t susChannelValues[12][4] = { - {3913, 3912, 3799, 4056}, - {3913, 3912, 3799, 4056}, - {3913, 3912, 3799, 4056}, - {3913, 3912, 3799, 4056}, - {3913, 3912, 3799, 4056}, - {3913, 3912, 3799, 4056}, - {3913, 3912, 3799, 4056}, - {3913, 3912, 3799, 4056}, - {3913, 3912, 3799, 4056}, - {3913, 3912, 3799, 4056}, - {3913, 3912, 3799, 4056}, - {3913, 3912, 3799, 4056}}; //[Bit] - float alphaBetaRaw[12][2]; //[°] - float alphaBetaCalibrated[12][2]; //[°] - float sunVectorBodyFrame[12][3]; //[-] + float alphaBetaRaw[2]; //[°] + // float coeffAlpha[9][10]; + // float coeffBeta[9][10]; + float alphaBetaCalibrated[2]; //[°] + float sunVectorBodyFrame[3]; //[-] - bool validFlag[12] = {returnvalue::OK, - returnvalue::OK,returnvalue::OK, - returnvalue::OK,returnvalue::OK, - returnvalue::OK,returnvalue::OK, - returnvalue::OK,returnvalue::OK, - returnvalue::OK,returnvalue::OK, - returnvalue::OK}; + bool validFlag[12] = {returnvalue::OK, returnvalue::OK, returnvalue::OK, returnvalue::OK, + returnvalue::OK, returnvalue::OK, returnvalue::OK, returnvalue::OK, + returnvalue::OK, returnvalue::OK, returnvalue::OK, returnvalue::OK}; - uint16_t channelValueCheckHigh = + static const uint8_t GNDREF = 4; + uint16_t susChannelValueCheckHigh = 4096; //=2^12[Bit]high borderline for the channel values of one sun sensor for validity Check - uint8_t channelValueCheckLow = + uint8_t susChannelValueCheckLow = 0; //[Bit]low borderline for the channel values of one sun sensor for validity Check - uint16_t channelValueSumHigh = + uint16_t susChannelValueSumHigh = 100; // 4096[Bit]high borderline for check if the sun sensor is illuminated by the sun or by // the reflection of sunlight from the moon/earth - uint8_t channelValueSumLow = + uint8_t susChannelValueSumLow = 0; //[Bit]low borderline for check if the sun sensor is illuminated // by the sun or by the reflection of sunlight from the moon/earth uint8_t completeCellWidth = 140, halfCellWidth = 70; //[°] Width of the calibration cells --> necessary for checking in // which cell a data point should be - - float coeffAlpha[12][9][10]; - float coeffBeta[12][9][10]; + uint16_t susChannelValueSum = 0; AcsParameters acsParameters; }; - #endif /* MISSION_CONTROLLER_ACS_SUSCONVERTER_H_ */ -- 2.34.1 From d726ce4e496972fa5f95e772fe2e837070c2195d Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 10 Oct 2022 09:43:52 +0200 Subject: [PATCH 040/101] permanently activated ACS_CTRL --- bsp_q7s/OBSWConfig.h.in | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bsp_q7s/OBSWConfig.h.in b/bsp_q7s/OBSWConfig.h.in index c20db3f1..a5f4f420 100644 --- a/bsp_q7s/OBSWConfig.h.in +++ b/bsp_q7s/OBSWConfig.h.in @@ -30,7 +30,7 @@ #define OBSW_ADD_SUN_SENSORS @OBSW_ADD_SUN_SENSORS@ #define OBSW_ADD_SUS_BOARD_ASS @OBSW_ADD_SUS_BOARD_ASS@ #define OBSW_ADD_ACS_BOARD @OBSW_ADD_ACS_BOARD@ -#define OBSW_ADD_ACS_CTRL @OBSW_ADD_ACS_CTRL@ +#define OBSW_ADD_ACS_CTRL 1 #define OBSW_ADD_GPS_CTRL @OBSW_ADD_GPS_CTRL@ #define OBSW_ADD_RW @OBSW_ADD_RW@ #define OBSW_ADD_RTD_DEVICES @OBSW_ADD_RTD_DEVICES@ -- 2.34.1 From 5cbbf4ceb2eb5eefab22baa664f72c6468ac2569 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 10 Oct 2022 09:44:28 +0200 Subject: [PATCH 041/101] corrected SUS dummy outputs to match student project --- dummies/SusDummy.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/dummies/SusDummy.cpp b/dummies/SusDummy.cpp index ba267d61..0c2feaac 100644 --- a/dummies/SusDummy.cpp +++ b/dummies/SusDummy.cpp @@ -51,7 +51,8 @@ void SusDummy::performControlOperation() { susSet.channels[0] = 3913; susSet.channels[1] = 3912; susSet.channels[2] = 3799; - susSet.channels[3] = 4056; + susSet.channels[3] = 3797; + susSet.channels[4] = 4056; susSet.commit(); } -- 2.34.1 From bbf4be1cfee605ef257b68c8dc21dd5c4509c179 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 10 Oct 2022 09:53:33 +0200 Subject: [PATCH 042/101] removed reduntant parts. fixed integers messing up divisions --- mission/controller/acs/SusConverter.cpp | 117 +----------------------- 1 file changed, 4 insertions(+), 113 deletions(-) diff --git a/mission/controller/acs/SusConverter.cpp b/mission/controller/acs/SusConverter.cpp index 7d8f5bd2..ea52f5a2 100644 --- a/mission/controller/acs/SusConverter.cpp +++ b/mission/controller/acs/SusConverter.cpp @@ -67,16 +67,17 @@ void SusConverter::calcAngle(lp_vec_t susChannel) { } void SusConverter::calibration(const float coeffAlpha[9][10], const float coeffBeta[9][10]) { - uint8_t index, k, l; + uint8_t index; + float k, l; // while loop iterates above all calibration cells to use the different calibration functions in // each cell k = 0; while (k < 3) { - k = k + 1; + k++; l = 0; while (l < 3) { - l = l + 1; + l++; // if-condition to check in which cell the data point has to be if ((alphaBetaRaw[0] > ((completeCellWidth * ((k - 1) / 3)) - halfCellWidth) && alphaBetaRaw[0] < ((completeCellWidth * (k / 3)) - halfCellWidth)) && @@ -131,113 +132,3 @@ float* SusConverter::getSunVectorSensorFrame(lp_vec_t susChannel, return calculateSunVector(); } -bool SusConverter::getValidFlag(uint8_t susNumber) { return validFlag[susNumber]; } - -float* SusConverter::TransferSunVector() { - float* sunVectorEIVE = 0; - sunVectorEIVE = new float[3]; - - uint8_t susAvail = 12; - int8_t basisMatrixUse[3][3]; - float sunVectorMatrixEIVE[3][12] = {0}; - float sunVectorMatrixBodyFrame[3][12]; - - for (uint8_t susNumber = 0; susNumber < 12; - susNumber++) { // save the sun vector of each SUS in their body frame into an array for - // further processing - float* SunVectorBodyFrame = &SunVectorBodyFrame[susNumber]; - sunVectorMatrixBodyFrame[0][susNumber] = SunVectorBodyFrame[0]; - sunVectorMatrixBodyFrame[1][susNumber] = SunVectorBodyFrame[1]; - sunVectorMatrixBodyFrame[2][susNumber] = SunVectorBodyFrame[2]; - } - - for (uint8_t susNumber = 0; susNumber < 12; susNumber++) { - if (getValidFlag(susNumber) == returnvalue::FAILED) { - susAvail -= 1; - } // if the SUS data is not valid -> - - for (uint8_t c1 = 0; c1 < 3; c1++) { - for (uint8_t c2 = 0; c2 < 3; c2++) { - switch (susNumber) { - case 0: - basisMatrixUse[c1][c2] = - acsParameters.susHandlingParameters.sus0orientationMatrix[c1][c2]; - break; - case 1: - basisMatrixUse[c1][c2] = - acsParameters.susHandlingParameters.sus1orientationMatrix[c1][c2]; - break; - case 2: - basisMatrixUse[c1][c2] = - acsParameters.susHandlingParameters.sus2orientationMatrix[c1][c2]; - break; - case 3: - basisMatrixUse[c1][c2] = - acsParameters.susHandlingParameters.sus3orientationMatrix[c1][c2]; - break; - case 4: - basisMatrixUse[c1][c2] = - acsParameters.susHandlingParameters.sus4orientationMatrix[c1][c2]; - break; - case 5: - basisMatrixUse[c1][c2] = - acsParameters.susHandlingParameters.sus5orientationMatrix[c1][c2]; - break; - case 6: - basisMatrixUse[c1][c2] = - acsParameters.susHandlingParameters.sus6orientationMatrix[c1][c2]; - break; - case 7: - basisMatrixUse[c1][c2] = - acsParameters.susHandlingParameters.sus7orientationMatrix[c1][c2]; - break; - case 8: - basisMatrixUse[c1][c2] = - acsParameters.susHandlingParameters.sus8orientationMatrix[c1][c2]; - break; - case 9: - basisMatrixUse[c1][c2] = - acsParameters.susHandlingParameters.sus9orientationMatrix[c1][c2]; - break; - case 10: - basisMatrixUse[c1][c2] = - acsParameters.susHandlingParameters.sus10orientationMatrix[c1][c2]; - break; - case 11: - basisMatrixUse[c1][c2] = - acsParameters.susHandlingParameters.sus11orientationMatrix[c1][c2]; - break; - } - } - } - - // matrix multiplication for transition in EIVE coordinatesystem - for (uint8_t p = 0; p < 3; p++) { - for (uint8_t q = 0; q < 3; q++) { - // normal matrix multiplication - sunVectorMatrixEIVE[p][susNumber] += - (basisMatrixUse[p][q] * sunVectorMatrixBodyFrame[q][susNumber]); - } - } - } - - if (susAvail > 0) { // Calculate one sun vector out of all sun vectors from the different SUS - for (uint8_t i = 0; i < 3; i++) { - float sum = 0; - for (uint8_t susNumber = 0; susNumber < 12; susNumber++) { - if (getValidFlag(susNumber) == returnvalue::OK) { - sum += sunVectorMatrixEIVE[i][susNumber]; - // printf("%f\n", SunVectorMatrixEIVE[i][susNumber]); - } - } - // ToDo: decide on length on sun vector - sunVectorEIVE[i] = sum; - } - VectorOperations::normalize(sunVectorEIVE, sunVectorEIVE, 3); - } else { - // No sus is valid - throw std::invalid_argument("No sun sensor is valid"); // throw error - } - - return sunVectorEIVE; -} -- 2.34.1 From f77b3498ec5f66c8bf215ef566488df8c0d37f92 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 10 Oct 2022 09:54:06 +0200 Subject: [PATCH 043/101] fixed inputs. removed outputs. minor fixes --- mission/controller/AcsController.cpp | 11 +- mission/controller/acs/AcsParameters.h | 4 +- mission/controller/acs/SensorProcessing.cpp | 155 ++++++++++---------- mission/controller/acs/SensorProcessing.h | 7 +- 4 files changed, 86 insertions(+), 91 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 2b0689c7..91d38eff 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -38,7 +38,7 @@ void AcsController::performControlOperation() { break; case SUBMODE_DETUMBLE: - // performDetumble(); + performDetumble(); break; case SUBMODE_PTG_GS: @@ -64,10 +64,9 @@ void AcsController::performControlOperation() { copySusData(); } } - sif::debug << susData.sus0.value[0] << "," << susData.sus0.value[1] << "," - << susData.sus0.value[2] << "," << susData.sus0.value[3] << "," - << susData.sus0.value[4] << "," << susData.sus0.value[5] << std::endl; - sif::debug << susData.sus0.isValid() << std::endl; + + mode = MODE_ON; + submode = SUBMODE_DETUMBLE; } void AcsController::performSafe() {} @@ -82,7 +81,7 @@ void AcsController::performDetumble() { timeval now; // = {0,0}; Clock::getClock_timeval(&now); - sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); + sensorProcessing.process(&susData, now, &sensorValues, &outputValues, &acsParameters); ReturnValue_t validMekf; navigation.useMekf(&sensorValues, &outputValues, &validMekf); double magMomMtq[3] = {0, 0, 0}; diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 39f2c3c6..c342dabc 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -16,11 +16,11 @@ public: AcsParameters(); virtual ~AcsParameters(); - +/* virtual ReturnValue_t getParameter(uint8_t domainId, uint16_t parameterId, ParameterWrapper *parameterWrapper, const ParameterWrapper *newValues, uint16_t startAtIndex); - +*/ struct OnBoardParams { double sampleTime = 0.1; // [s] } onBoardParams; diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index 933800e2..c5db92ad 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -144,29 +144,29 @@ bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const return true; } -void SensorProcessing::processSus(acsctrl::SusDataRaw susData, timeval timeOfSusMeasurement, +void SensorProcessing::processSus(acsctrl::SusDataRaw *susData, timeval timeOfSusMeasurement, const AcsParameters::SusHandlingParameters *susParameters, const AcsParameters::SunModelParameters *sunModelParameters, double *sunDirEst, bool *sunDirEstValid, double *sunVectorInertial, bool *sunVectorInertialValid, double *sunVectorDerivative, bool *sunVectorDerivativeValid) { - susData.sus0.setValid(susConverter.checkSunSensorData(susData.sus0)); - susData.sus1.setValid(susConverter.checkSunSensorData(susData.sus1)); - susData.sus2.setValid(susConverter.checkSunSensorData(susData.sus2)); - susData.sus3.setValid(susConverter.checkSunSensorData(susData.sus3)); - susData.sus4.setValid(susConverter.checkSunSensorData(susData.sus4)); - susData.sus5.setValid(susConverter.checkSunSensorData(susData.sus5)); - susData.sus6.setValid(susConverter.checkSunSensorData(susData.sus6)); - susData.sus7.setValid(susConverter.checkSunSensorData(susData.sus7)); - susData.sus8.setValid(susConverter.checkSunSensorData(susData.sus8)); - susData.sus9.setValid(susConverter.checkSunSensorData(susData.sus9)); - susData.sus10.setValid(susConverter.checkSunSensorData(susData.sus10)); - susData.sus11.setValid(susConverter.checkSunSensorData(susData.sus11)); + susData->sus0.setValid(susConverter.checkSunSensorData(susData->sus0)); + susData->sus1.setValid(susConverter.checkSunSensorData(susData->sus1)); + susData->sus2.setValid(susConverter.checkSunSensorData(susData->sus2)); + susData->sus3.setValid(susConverter.checkSunSensorData(susData->sus3)); + susData->sus4.setValid(susConverter.checkSunSensorData(susData->sus4)); + susData->sus5.setValid(susConverter.checkSunSensorData(susData->sus5)); + susData->sus6.setValid(susConverter.checkSunSensorData(susData->sus6)); + susData->sus7.setValid(susConverter.checkSunSensorData(susData->sus7)); + susData->sus8.setValid(susConverter.checkSunSensorData(susData->sus8)); + susData->sus9.setValid(susConverter.checkSunSensorData(susData->sus9)); + susData->sus10.setValid(susConverter.checkSunSensorData(susData->sus10)); + susData->sus11.setValid(susConverter.checkSunSensorData(susData->sus11)); - if (!susData.sus0.isValid() && !susData.sus1.isValid() && !susData.sus2.isValid() && - !susData.sus3.isValid() && !susData.sus4.isValid() && !susData.sus5.isValid() && - !susData.sus6.isValid() && !susData.sus7.isValid() && !susData.sus8.isValid() && - !susData.sus9.isValid() && !susData.sus10.isValid() && !susData.sus11.isValid()) { + if (!susData->sus0.isValid() && !susData->sus1.isValid() && !susData->sus2.isValid() && + !susData->sus3.isValid() && !susData->sus4.isValid() && !susData->sus5.isValid() && + !susData->sus6.isValid() && !susData->sus7.isValid() && !susData->sus8.isValid() && + !susData->sus9.isValid() && !susData->sus10.isValid() && !susData->sus11.isValid()) { *sunDirEstValid = false; return; } else { @@ -177,97 +177,97 @@ void SensorProcessing::processSus(acsctrl::SusDataRaw susData, timeval timeOfSus sus6VecBody[3] = {0, 0, 0}, sus7VecBody[3] = {0, 0, 0}, sus8VecBody[3] = {0, 0, 0}, sus9VecBody[3] = {0, 0, 0}, sus10VecBody[3] = {0, 0, 0}, sus11VecBody[3] = {0, 0, 0}; - if (susData.sus0.isValid()) { + if (susData->sus0.isValid()) { MatrixOperations::multiply( susParameters->sus0orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData.sus0, susParameters->sus0coeffAlpha, + susConverter.getSunVectorSensorFrame(susData->sus0, susParameters->sus0coeffAlpha, susParameters->sus0coeffBeta), sus0VecBody, 3, 3, 1); } - if (susData.sus1.isValid()) { + if (susData->sus1.isValid()) { MatrixOperations::multiply( susParameters->sus1orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData.sus1, susParameters->sus1coeffAlpha, + susConverter.getSunVectorSensorFrame(susData->sus1, susParameters->sus1coeffAlpha, susParameters->sus1coeffBeta), sus1VecBody, 3, 3, 1); } - if (susData.sus2.isValid()) { + if (susData->sus2.isValid()) { MatrixOperations::multiply( susParameters->sus2orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData.sus2, susParameters->sus2coeffAlpha, + susConverter.getSunVectorSensorFrame(susData->sus2, susParameters->sus2coeffAlpha, susParameters->sus2coeffBeta), sus2VecBody, 3, 3, 1); } - if (susData.sus3.isValid()) { + if (susData->sus3.isValid()) { MatrixOperations::multiply( susParameters->sus3orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData.sus3, susParameters->sus3coeffAlpha, + susConverter.getSunVectorSensorFrame(susData->sus3, susParameters->sus3coeffAlpha, susParameters->sus3coeffBeta), sus3VecBody, 3, 3, 1); } - if (susData.sus4.isValid()) { + if (susData->sus4.isValid()) { MatrixOperations::multiply( susParameters->sus4orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData.sus4, susParameters->sus4coeffAlpha, + susConverter.getSunVectorSensorFrame(susData->sus4, susParameters->sus4coeffAlpha, susParameters->sus4coeffBeta), sus4VecBody, 3, 3, 1); } - if (susData.sus5.isValid()) { + if (susData->sus5.isValid()) { MatrixOperations::multiply( susParameters->sus5orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData.sus5, susParameters->sus5coeffAlpha, + susConverter.getSunVectorSensorFrame(susData->sus5, susParameters->sus5coeffAlpha, susParameters->sus5coeffBeta), sus5VecBody, 3, 3, 1); } - if (susData.sus6.isValid()) { + if (susData->sus6.isValid()) { MatrixOperations::multiply( susParameters->sus6orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData.sus6, susParameters->sus6coeffAlpha, + susConverter.getSunVectorSensorFrame(susData->sus6, susParameters->sus6coeffAlpha, susParameters->sus6coeffBeta), sus6VecBody, 3, 3, 1); } - if (susData.sus7.isValid()) { + if (susData->sus7.isValid()) { MatrixOperations::multiply( susParameters->sus7orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData.sus7, susParameters->sus7coeffAlpha, + susConverter.getSunVectorSensorFrame(susData->sus7, susParameters->sus7coeffAlpha, susParameters->sus7coeffBeta), sus7VecBody, 3, 3, 1); } - if (susData.sus8.isValid()) { + if (susData->sus8.isValid()) { MatrixOperations::multiply( susParameters->sus8orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData.sus8, susParameters->sus8coeffAlpha, + susConverter.getSunVectorSensorFrame(susData->sus8, susParameters->sus8coeffAlpha, susParameters->sus8coeffBeta), sus8VecBody, 3, 3, 1); } - if (susData.sus9.isValid()) { + if (susData->sus9.isValid()) { MatrixOperations::multiply( susParameters->sus9orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData.sus9, susParameters->sus9coeffAlpha, + susConverter.getSunVectorSensorFrame(susData->sus9, susParameters->sus9coeffAlpha, susParameters->sus9coeffBeta), sus9VecBody, 3, 3, 1); } - if (susData.sus10.isValid()) { + if (susData->sus10.isValid()) { MatrixOperations::multiply( susParameters->sus10orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData.sus10, susParameters->sus10coeffAlpha, + susConverter.getSunVectorSensorFrame(susData->sus10, susParameters->sus10coeffAlpha, susParameters->sus10coeffBeta), sus10VecBody, 3, 3, 1); } - if (susData.sus11.isValid()) { + if (susData->sus11.isValid()) { MatrixOperations::multiply( susParameters->sus11orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData.sus11, susParameters->sus11coeffAlpha, + susConverter.getSunVectorSensorFrame(susData->sus11, susParameters->sus11coeffAlpha, susParameters->sus11coeffBeta), sus11VecBody, 3, 3, 1); } /* ------ Mean Value: susDirEst ------ */ - // Timo already done - bool validIds[12] = {susData.sus0.isValid(), susData.sus1.isValid(), susData.sus2.isValid(), - susData.sus3.isValid(), susData.sus4.isValid(), susData.sus5.isValid(), - susData.sus6.isValid(), susData.sus7.isValid(), susData.sus8.isValid(), - susData.sus9.isValid(), susData.sus10.isValid(), susData.sus11.isValid()}; + bool validIds[12] = { + susData->sus0.isValid(), susData->sus1.isValid(), susData->sus2.isValid(), + susData->sus3.isValid(), susData->sus4.isValid(), susData->sus5.isValid(), + susData->sus6.isValid(), susData->sus7.isValid(), susData->sus8.isValid(), + susData->sus9.isValid(), susData->sus10.isValid(), susData->sus11.isValid()}; float susVecBody[3][12] = {{sus0VecBody[0], sus1VecBody[0], sus2VecBody[0], sus3VecBody[0], sus4VecBody[0], sus5VecBody[0], sus6VecBody[0], sus7VecBody[0], sus8VecBody[0], sus9VecBody[0], sus10VecBody[0], sus11VecBody[0]}, @@ -279,7 +279,7 @@ void SensorProcessing::processSus(acsctrl::SusDataRaw susData, timeval timeOfSus sus8VecBody[2], sus9VecBody[2], sus10VecBody[2], sus11VecBody[2]}}; double susMeanValue[3] = {0, 0, 0}; - uint8_t validSusCounter = 0; + float validSusCounter = 0; for (uint8_t i = 0; i < 12; i++) { if (validIds[i]) { susMeanValue[0] += susVecBody[0][i]; @@ -407,40 +407,35 @@ void SensorProcessing::processGps(const double gps0latitude, const double gps0lo } } -void SensorProcessing::process(timeval now, ACS::SensorValues *sensorValues, - ACS::OutputValues *outputValues, +void SensorProcessing::process(acsctrl::SusDataRaw *susData, timeval now, + ACS::SensorValues *sensorValues, ACS::OutputValues *outputValues, const AcsParameters *acsParameters) { - sensorValues->update(); - processGps(sensorValues->gps0latitude, sensorValues->gps0longitude, sensorValues->gps0Valid, - &outputValues->gcLatitude, &outputValues->gdLongitude); + // sensorValues->update(); + // processGps(sensorValues->gps0latitude, sensorValues->gps0longitude, sensorValues->gps0Valid, + // &outputValues->gcLatitude, &outputValues->gdLongitude); - /*outputValues->mgmUpdated = processMgm(sensorValues->mgm0, sensorValues->mgm0Valid, - sensorValues->mgm1, sensorValues->mgm1Valid, - sensorValues->mgm2, sensorValues->mgm2Valid, - sensorValues->mgm3, sensorValues->mgm3Valid, - sensorValues->mgm4, sensorValues->mgm4Valid, now, - &acsParameters->mgmHandlingParameters, outputValues->gcLatitude, - outputValues->gdLongitude, sensorValues->gps0altitude, - sensorValues->gps0Valid, - outputValues->magFieldEst, &outputValues->magFieldEstValid, - outputValues->magFieldModel, &outputValues->magFieldModelValid, - outputValues->magneticFieldVectorDerivative, - &outputValues->magneticFieldVectorDerivativeValid); // VALID outputs- PoolVariable ? + // outputValues->mgmUpdated = processMgm(sensorValues->mgm0, sensorValues->mgm0Valid, + // sensorValues->mgm1, sensorValues->mgm1Valid, + // sensorValues->mgm2, sensorValues->mgm2Valid, + // sensorValues->mgm3, sensorValues->mgm3Valid, + // sensorValues->mgm4, sensorValues->mgm4Valid, now, + // &acsParameters->mgmHandlingParameters, outputValues->gcLatitude, + // outputValues->gdLongitude, sensorValues->gps0altitude, + // sensorValues->gps0Valid, + // outputValues->magFieldEst, &outputValues->magFieldEstValid, + // outputValues->magFieldModel, &outputValues->magFieldModelValid, + // outputValues->magneticFieldVectorDerivative, + // &outputValues->magneticFieldVectorDerivativeValid); // VALID outputs- PoolVariable ? - processSus(sensorValues->sus0, sensorValues->sus0Valid, sensorValues->sus1, - sensorValues->sus1Valid, sensorValues->sus2, sensorValues->sus2Valid, sensorValues->sus3, - sensorValues->sus3Valid, sensorValues->sus4, sensorValues->sus4Valid, sensorValues->sus5, - sensorValues->sus5Valid, sensorValues->sus6, sensorValues->sus6Valid, sensorValues->sus7, - sensorValues->sus7Valid, sensorValues->sus8, sensorValues->sus8Valid, sensorValues->sus9, - sensorValues->sus9Valid, sensorValues->sus10, sensorValues->sus10Valid, sensorValues->sus11, - sensorValues->sus11Valid, now, &acsParameters->susHandlingParameters, - &acsParameters->sunModelParameters, outputValues->sunDirEst, &outputValues->sunDirEstValid, - outputValues->sunDirModel, &outputValues->sunDirModelValid, - outputValues->sunVectorDerivative, &outputValues->sunVectorDerivativeValid); // - VALID outputs ? -*/ - processRmu(sensorValues->rmu0, sensorValues->rmu0Valid, sensorValues->rmu1, - sensorValues->rmu1Valid, sensorValues->rmu2, sensorValues->rmu2Valid, now, - &acsParameters->rmuHandlingParameters, outputValues->satRateEst, - &outputValues->satRateEstValid); + processSus(susData, now, &acsParameters->susHandlingParameters, + &acsParameters->sunModelParameters, outputValues->sunDirEst, + &outputValues->sunDirEstValid, outputValues->sunDirModel, + &outputValues->sunDirModelValid, outputValues->sunVectorDerivative, + &outputValues->sunVectorDerivativeValid); + // VALID outputs ? + + // processRmu(sensorValues->rmu0, sensorValues->rmu0Valid, sensorValues->rmu1, + // sensorValues->rmu1Valid, sensorValues->rmu2, sensorValues->rmu2Valid, now, + // &acsParameters->rmuHandlingParameters, outputValues->satRateEst, + // &outputValues->satRateEstValid); } diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h index baa9c5b6..bde4f34e 100644 --- a/mission/controller/acs/SensorProcessing.h +++ b/mission/controller/acs/SensorProcessing.h @@ -9,11 +9,11 @@ #include //uint8_t #include /*purpose, timeval ?*/ -#include "SusConverter.h" #include "../controllerdefinitions/AcsCtrlDefinitions.h" #include "AcsParameters.h" #include "OutputValues.h" #include "SensorValues.h" +#include "SusConverter.h" #include "config/classIds.h" /*Planned: @@ -35,7 +35,8 @@ class SensorProcessing { SensorProcessing(AcsParameters *acsParameters_); virtual ~SensorProcessing(); - void process(timeval now, ACS::SensorValues *sensorValues, ACS::OutputValues *outputValues, + void process(acsctrl::SusDataRaw *susData, timeval now, ACS::SensorValues *sensorValues, + ACS::OutputValues *outputValues, const AcsParameters *acsParameters); // Will call protected functions private: protected: @@ -49,7 +50,7 @@ class SensorProcessing { bool *magFieldModelValid, double *magneticFieldVectorDerivative, bool *magneticFieldVectorDerivativeValid); // Output - void processSus(acsctrl::SusDataRaw susData, timeval timeOfSusMeasurement, + void processSus(acsctrl::SusDataRaw *susData, timeval timeOfSusMeasurement, const AcsParameters::SusHandlingParameters *susParameters, const AcsParameters::SunModelParameters *sunModelParameters, double *sunDirEst, bool *sunDirEstValid, double *sunVectorInertial, bool *sunVectorInertialValid, -- 2.34.1 From d9f2dfa72505defad9950314bfa0bf349ad2e232 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 10 Oct 2022 15:58:51 +0200 Subject: [PATCH 044/101] fixed warnings --- 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 a6a91a81..7d9cd8df 100644 --- a/mission/controller/acs/Guidance.cpp +++ b/mission/controller/acs/Guidance.cpp @@ -73,7 +73,7 @@ void Guidance::targetQuatPtg(ACS::SensorValues* sensorValues, ACS::OutputValues double omegaEarth = acsParameters.targetModeControllerParameters.omegaEarth; // TEST SECTION ! - double dcmTEST[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + //double dcmTEST[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; //MatrixOperations::multiply(&acsParameters.magnetorquesParameter.mtq0orientationMatrix, dcmTEST, dcmTEST, 3, 3, 3); MatrixOperations::multiply(*dcmDot, *dcmEJ, *dcmEJDot, 3, 3, 3); @@ -309,7 +309,7 @@ void Guidance::getDistributionMatrixRw(ACS::SensorValues* sensorValues, double * rwPseudoInv[11] = acsParameters.rwMatrices.without2[3][2]; } - else if ((sensorValues->validRw0) && (sensorValues->validRw1) && (sensorValues->validRw2) && (sensorValues->validRw3)) { + else if ((sensorValues->validRw0) && (sensorValues->validRw1) && (sensorValues->validRw2) && !(sensorValues->validRw3)) { rwPseudoInv[0] = acsParameters.rwMatrices.without3[0][0]; rwPseudoInv[1] = acsParameters.rwMatrices.without3[0][1]; -- 2.34.1 From f0fec11ad7fd289f2368054601b42c9a0ee05deb Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 10 Oct 2022 16:00:31 +0200 Subject: [PATCH 045/101] set channel output valid flag to true --- dummies/SusDummy.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/dummies/SusDummy.cpp b/dummies/SusDummy.cpp index 0c2feaac..d209368b 100644 --- a/dummies/SusDummy.cpp +++ b/dummies/SusDummy.cpp @@ -42,12 +42,12 @@ void SusDummy::performControlOperation() { value = sin(iteration / 80. * M_PI + 10) * 10 - 10; susSet.read(); - susSet.temperatureCelcius = value; - if ((iteration % 100) < 20) { - susSet.setValidity(false, true); - } else { - susSet.setValidity(true, true); - } +// susSet.temperatureCelcius = value; +// if ((iteration % 100) < 20) { +// susSet.setValidity(false, true); +// } else { +// susSet.setValidity(true, true); +// } susSet.channels[0] = 3913; susSet.channels[1] = 3912; susSet.channels[2] = 3799; @@ -60,7 +60,7 @@ ReturnValue_t SusDummy::initializeLocalDataPool(localpool::DataPool& localDataPo LocalDataPoolManager& poolManager) { localDataPoolMap.emplace(SUS::SusPoolIds::TEMPERATURE_C, new PoolEntry({0}, 1, true)); localDataPoolMap.emplace(SUS::SusPoolIds::CHANNEL_VEC, - new PoolEntry({0, 0, 0, 0, 0, 0})); + new PoolEntry({0, 0, 0, 0, 0, 0},true)); return returnvalue::OK; } -- 2.34.1 From 82e9c6d092bca2e7c9edd6202f3551b559bba412 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 10 Oct 2022 16:02:17 +0200 Subject: [PATCH 046/101] comments --- mission/controller/AcsController.cpp | 3 +++ mission/controller/acs/AcsParameters.h | 3 +-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 91d38eff..785a6906 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -65,8 +65,11 @@ void AcsController::performControlOperation() { } } + + // DEBUG : REMOVE AFTER COMPLETION mode = MODE_ON; submode = SUBMODE_DETUMBLE; + // DEBUG END } void AcsController::performSafe() {} diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index c342dabc..85ceaec0 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -892,10 +892,9 @@ public: float omega_0 = 282.94 * M_PI / 180.; //RAAN plus argument of perigee float m_0 = 357.5256; //coefficients for mean anomaly float dm = 35999.049; //coefficients for mean anomaly - // ToDo: check correct assignment of e and e1. Both were assigned to e before float e = 23.4392911 * M_PI / 180.; //angle of earth's rotation axis float e1 = 0.74508 * M_PI / 180.; - // + float p1 = 6892. / 3600. * M_PI / 180.; //some parameter float p2 = 72. / 3600. * M_PI / 180.; //some parameter } sunModelParameters; -- 2.34.1 From 076e67dd0bade52bfa0c7d8e2a8c5653b8fe8bad Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 10 Oct 2022 16:02:57 +0200 Subject: [PATCH 047/101] switched sensor input from AcsController to SensorValues --- mission/controller/acs/SensorProcessing.cpp | 179 ++++++++++++-------- mission/controller/acs/SensorProcessing.h | 22 +-- mission/controller/acs/SensorValues.cpp | 57 +++++-- mission/controller/acs/SensorValues.h | 142 +++++++--------- mission/controller/acs/SusConverter.cpp | 39 ++--- mission/controller/acs/SusConverter.h | 8 +- 6 files changed, 241 insertions(+), 206 deletions(-) diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index c5db92ad..749ec373 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -19,8 +19,6 @@ #include "util/MathOperations.h" using namespace Math; -// Thought: Maybe separate file for transforming of sensor values -// into geometry frame and body frame SensorProcessing::SensorProcessing(AcsParameters *acsParameters_) : savedMagFieldEst{0, 0, 0} { validMagField = false; @@ -144,29 +142,56 @@ bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const return true; } -void SensorProcessing::processSus(acsctrl::SusDataRaw *susData, timeval timeOfSusMeasurement, - const AcsParameters::SusHandlingParameters *susParameters, - const AcsParameters::SunModelParameters *sunModelParameters, - double *sunDirEst, bool *sunDirEstValid, - double *sunVectorInertial, bool *sunVectorInertialValid, - double *sunVectorDerivative, bool *sunVectorDerivativeValid) { - susData->sus0.setValid(susConverter.checkSunSensorData(susData->sus0)); - susData->sus1.setValid(susConverter.checkSunSensorData(susData->sus1)); - susData->sus2.setValid(susConverter.checkSunSensorData(susData->sus2)); - susData->sus3.setValid(susConverter.checkSunSensorData(susData->sus3)); - susData->sus4.setValid(susConverter.checkSunSensorData(susData->sus4)); - susData->sus5.setValid(susConverter.checkSunSensorData(susData->sus5)); - susData->sus6.setValid(susConverter.checkSunSensorData(susData->sus6)); - susData->sus7.setValid(susConverter.checkSunSensorData(susData->sus7)); - susData->sus8.setValid(susConverter.checkSunSensorData(susData->sus8)); - susData->sus9.setValid(susConverter.checkSunSensorData(susData->sus9)); - susData->sus10.setValid(susConverter.checkSunSensorData(susData->sus10)); - susData->sus11.setValid(susConverter.checkSunSensorData(susData->sus11)); +void SensorProcessing::processSus( + const uint16_t *sus0Value, bool sus0valid, const uint16_t *sus1Value, bool sus1valid, + const uint16_t *sus2Value, bool sus2valid, const uint16_t *sus3Value, bool sus3valid, + const uint16_t *sus4Value, bool sus4valid, const uint16_t *sus5Value, bool sus5valid, + const uint16_t *sus6Value, bool sus6valid, const uint16_t *sus7Value, bool sus7valid, + const uint16_t *sus8Value, bool sus8valid, const uint16_t *sus9Value, bool sus9valid, + const uint16_t *sus10Value, bool sus10valid, const uint16_t *sus11Value, bool sus11valid, + timeval timeOfSusMeasurement, const AcsParameters::SusHandlingParameters *susParameters, + const AcsParameters::SunModelParameters *sunModelParameters, double *sunDirEst, + bool *sunDirEstValid, double *sunVectorInertial, bool *sunVectorInertialValid, + double *sunVectorDerivative, bool *sunVectorDerivativeValid) { + if (sus0valid) { + sus0valid = susConverter.checkSunSensorData(sus0Value); + } + if (sus1valid) { + sus1valid = susConverter.checkSunSensorData(sus1Value); + } + if (sus2valid) { + sus2valid = susConverter.checkSunSensorData(sus2Value); + } + if (sus3valid) { + sus3valid = susConverter.checkSunSensorData(sus3Value); + } + if (sus4valid) { + sus4valid = susConverter.checkSunSensorData(sus4Value); + } + if (sus5valid) { + sus5valid = susConverter.checkSunSensorData(sus5Value); + } + if (sus6valid) { + sus6valid = susConverter.checkSunSensorData(sus6Value); + } + if (sus7valid) { + sus7valid = susConverter.checkSunSensorData(sus7Value); + } + if (sus8valid) { + sus8valid = susConverter.checkSunSensorData(sus8Value); + } + if (sus9valid) { + sus9valid = susConverter.checkSunSensorData(sus9Value); + } + if (sus10valid) { + sus10valid = susConverter.checkSunSensorData(sus10Value); + } + if (sus11valid) { + sus11valid = susConverter.checkSunSensorData(sus11Value); + } - if (!susData->sus0.isValid() && !susData->sus1.isValid() && !susData->sus2.isValid() && - !susData->sus3.isValid() && !susData->sus4.isValid() && !susData->sus5.isValid() && - !susData->sus6.isValid() && !susData->sus7.isValid() && !susData->sus8.isValid() && - !susData->sus9.isValid() && !susData->sus10.isValid() && !susData->sus11.isValid()) { + if (!sus0valid && !sus1valid && !sus2valid && !sus3valid && !sus4valid && !sus5valid && + !sus6valid && !sus7valid && !sus8valid && !sus9valid && !sus10valid && !sus11valid) { *sunDirEstValid = false; return; } else { @@ -177,97 +202,94 @@ void SensorProcessing::processSus(acsctrl::SusDataRaw *susData, timeval timeOfSu sus6VecBody[3] = {0, 0, 0}, sus7VecBody[3] = {0, 0, 0}, sus8VecBody[3] = {0, 0, 0}, sus9VecBody[3] = {0, 0, 0}, sus10VecBody[3] = {0, 0, 0}, sus11VecBody[3] = {0, 0, 0}; - if (susData->sus0.isValid()) { + if (sus0valid) { MatrixOperations::multiply( susParameters->sus0orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData->sus0, susParameters->sus0coeffAlpha, + susConverter.getSunVectorSensorFrame(sus0Value, susParameters->sus0coeffAlpha, susParameters->sus0coeffBeta), sus0VecBody, 3, 3, 1); } - if (susData->sus1.isValid()) { + if (sus1valid) { MatrixOperations::multiply( susParameters->sus1orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData->sus1, susParameters->sus1coeffAlpha, + susConverter.getSunVectorSensorFrame(sus1Value, susParameters->sus1coeffAlpha, susParameters->sus1coeffBeta), sus1VecBody, 3, 3, 1); } - if (susData->sus2.isValid()) { + if (sus2valid) { MatrixOperations::multiply( susParameters->sus2orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData->sus2, susParameters->sus2coeffAlpha, + susConverter.getSunVectorSensorFrame(sus2Value, susParameters->sus2coeffAlpha, susParameters->sus2coeffBeta), sus2VecBody, 3, 3, 1); } - if (susData->sus3.isValid()) { + if (sus3valid) { MatrixOperations::multiply( susParameters->sus3orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData->sus3, susParameters->sus3coeffAlpha, + susConverter.getSunVectorSensorFrame(sus3Value, susParameters->sus3coeffAlpha, susParameters->sus3coeffBeta), sus3VecBody, 3, 3, 1); } - if (susData->sus4.isValid()) { + if (sus4valid) { MatrixOperations::multiply( susParameters->sus4orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData->sus4, susParameters->sus4coeffAlpha, + susConverter.getSunVectorSensorFrame(sus4Value, susParameters->sus4coeffAlpha, susParameters->sus4coeffBeta), sus4VecBody, 3, 3, 1); } - if (susData->sus5.isValid()) { + if (sus5valid) { MatrixOperations::multiply( susParameters->sus5orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData->sus5, susParameters->sus5coeffAlpha, + susConverter.getSunVectorSensorFrame(sus5Value, susParameters->sus5coeffAlpha, susParameters->sus5coeffBeta), sus5VecBody, 3, 3, 1); } - if (susData->sus6.isValid()) { + if (sus6valid) { MatrixOperations::multiply( susParameters->sus6orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData->sus6, susParameters->sus6coeffAlpha, + susConverter.getSunVectorSensorFrame(sus6Value, susParameters->sus6coeffAlpha, susParameters->sus6coeffBeta), sus6VecBody, 3, 3, 1); } - if (susData->sus7.isValid()) { + if (sus7valid) { MatrixOperations::multiply( susParameters->sus7orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData->sus7, susParameters->sus7coeffAlpha, + susConverter.getSunVectorSensorFrame(sus7Value, susParameters->sus7coeffAlpha, susParameters->sus7coeffBeta), sus7VecBody, 3, 3, 1); } - if (susData->sus8.isValid()) { + if (sus8valid) { MatrixOperations::multiply( susParameters->sus8orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData->sus8, susParameters->sus8coeffAlpha, + susConverter.getSunVectorSensorFrame(sus8Value, susParameters->sus8coeffAlpha, susParameters->sus8coeffBeta), sus8VecBody, 3, 3, 1); } - if (susData->sus9.isValid()) { + if (sus9valid) { MatrixOperations::multiply( susParameters->sus9orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData->sus9, susParameters->sus9coeffAlpha, + susConverter.getSunVectorSensorFrame(sus9Value, susParameters->sus9coeffAlpha, susParameters->sus9coeffBeta), sus9VecBody, 3, 3, 1); } - if (susData->sus10.isValid()) { + if (sus10valid) { MatrixOperations::multiply( susParameters->sus10orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData->sus10, susParameters->sus10coeffAlpha, + susConverter.getSunVectorSensorFrame(sus10Value, susParameters->sus10coeffAlpha, susParameters->sus10coeffBeta), sus10VecBody, 3, 3, 1); } - if (susData->sus11.isValid()) { + if (sus11valid) { MatrixOperations::multiply( susParameters->sus11orientationMatrix[0], - susConverter.getSunVectorSensorFrame(susData->sus11, susParameters->sus11coeffAlpha, + susConverter.getSunVectorSensorFrame(sus11Value, susParameters->sus11coeffAlpha, susParameters->sus11coeffBeta), sus11VecBody, 3, 3, 1); } /* ------ Mean Value: susDirEst ------ */ - bool validIds[12] = { - susData->sus0.isValid(), susData->sus1.isValid(), susData->sus2.isValid(), - susData->sus3.isValid(), susData->sus4.isValid(), susData->sus5.isValid(), - susData->sus6.isValid(), susData->sus7.isValid(), susData->sus8.isValid(), - susData->sus9.isValid(), susData->sus10.isValid(), susData->sus11.isValid()}; + bool validIds[12] = {sus0valid, sus1valid, sus2valid, sus3valid, sus4valid, sus5valid, + sus6valid, sus7valid, sus8valid, sus9valid, sus10valid, sus11valid}; float susVecBody[3][12] = {{sus0VecBody[0], sus1VecBody[0], sus2VecBody[0], sus3VecBody[0], sus4VecBody[0], sus5VecBody[0], sus6VecBody[0], sus7VecBody[0], sus8VecBody[0], sus9VecBody[0], sus10VecBody[0], sus11VecBody[0]}, @@ -279,17 +301,14 @@ void SensorProcessing::processSus(acsctrl::SusDataRaw *susData, timeval timeOfSu sus8VecBody[2], sus9VecBody[2], sus10VecBody[2], sus11VecBody[2]}}; double susMeanValue[3] = {0, 0, 0}; - float validSusCounter = 0; for (uint8_t i = 0; i < 12; i++) { if (validIds[i]) { susMeanValue[0] += susVecBody[0][i]; susMeanValue[1] += susVecBody[1][i]; susMeanValue[2] += susVecBody[2][i]; - validSusCounter += 1; } } - double divisor = 1 / validSusCounter; - VectorOperations::mulScalar(susMeanValue, divisor, sunDirEst, 3); + VectorOperations::normalize(susMeanValue, sunDirEst, 3); *sunDirEstValid = true; } @@ -410,26 +429,40 @@ void SensorProcessing::processGps(const double gps0latitude, const double gps0lo void SensorProcessing::process(acsctrl::SusDataRaw *susData, timeval now, ACS::SensorValues *sensorValues, ACS::OutputValues *outputValues, const AcsParameters *acsParameters) { - // sensorValues->update(); + sensorValues->update(); // processGps(sensorValues->gps0latitude, sensorValues->gps0longitude, sensorValues->gps0Valid, // &outputValues->gcLatitude, &outputValues->gdLongitude); - // outputValues->mgmUpdated = processMgm(sensorValues->mgm0, sensorValues->mgm0Valid, - // sensorValues->mgm1, sensorValues->mgm1Valid, - // sensorValues->mgm2, sensorValues->mgm2Valid, - // sensorValues->mgm3, sensorValues->mgm3Valid, - // sensorValues->mgm4, sensorValues->mgm4Valid, now, - // &acsParameters->mgmHandlingParameters, outputValues->gcLatitude, - // outputValues->gdLongitude, sensorValues->gps0altitude, - // sensorValues->gps0Valid, - // outputValues->magFieldEst, &outputValues->magFieldEstValid, - // outputValues->magFieldModel, &outputValues->magFieldModelValid, - // outputValues->magneticFieldVectorDerivative, - // &outputValues->magneticFieldVectorDerivativeValid); // VALID outputs- PoolVariable ? + outputValues->mgmUpdated = processMgm( + sensorValues->mgm0Lis3Set.fieldStrengths.value, + sensorValues->mgm0Lis3Set.fieldStrengths.isValid(), + sensorValues->mgm1Rm3100Set.fieldStrengths.value, + sensorValues->mgm1Rm3100Set.fieldStrengths.isValid(), + sensorValues->mgm2Lis3Set.fieldStrengths.value, + sensorValues->mgm2Lis3Set.fieldStrengths.isValid(), + sensorValues->mgm3Rm3100Set.fieldStrengths.value, + sensorValues->mgm3Rm3100Set.fieldStrengths.isValid(), sensorValues->imtqMgmSet.mtmRawNt.value, + sensorValues->imtqMgmSet.mtmRawNt.isValid(), now, &acsParameters->mgmHandlingParameters, + outputValues->gcLatitude, outputValues->gdLongitude, sensorValues->gps0altitude, + sensorValues->gps0Valid, outputValues->magFieldEst, &outputValues->magFieldEstValid, + outputValues->magFieldModel, &outputValues->magFieldModelValid, + outputValues->magneticFieldVectorDerivative, + &outputValues->magneticFieldVectorDerivativeValid); // VALID outputs- PoolVariable ? - processSus(susData, now, &acsParameters->susHandlingParameters, - &acsParameters->sunModelParameters, outputValues->sunDirEst, - &outputValues->sunDirEstValid, outputValues->sunDirModel, + processSus(sensorValues->susSets[0].channels.value, sensorValues->susSets[0].channels.isValid(), + sensorValues->susSets[1].channels.value, sensorValues->susSets[1].channels.isValid(), + sensorValues->susSets[2].channels.value, sensorValues->susSets[2].channels.isValid(), + sensorValues->susSets[3].channels.value, sensorValues->susSets[3].channels.isValid(), + sensorValues->susSets[4].channels.value, sensorValues->susSets[4].channels.isValid(), + sensorValues->susSets[5].channels.value, sensorValues->susSets[5].channels.isValid(), + sensorValues->susSets[6].channels.value, sensorValues->susSets[6].channels.isValid(), + sensorValues->susSets[7].channels.value, sensorValues->susSets[7].channels.isValid(), + sensorValues->susSets[8].channels.value, sensorValues->susSets[8].channels.isValid(), + sensorValues->susSets[9].channels.value, sensorValues->susSets[9].channels.isValid(), + sensorValues->susSets[10].channels.value, sensorValues->susSets[10].channels.isValid(), + sensorValues->susSets[11].channels.value, sensorValues->susSets[11].channels.isValid(), + now, &acsParameters->susHandlingParameters, &acsParameters->sunModelParameters, + outputValues->sunDirEst, &outputValues->sunDirEstValid, outputValues->sunDirModel, &outputValues->sunDirModelValid, outputValues->sunVectorDerivative, &outputValues->sunVectorDerivativeValid); // VALID outputs ? diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h index bde4f34e..df2b2a37 100644 --- a/mission/controller/acs/SensorProcessing.h +++ b/mission/controller/acs/SensorProcessing.h @@ -16,18 +16,6 @@ #include "SusConverter.h" #include "config/classIds.h" -/*Planned: - * - Fusion of Sensor Measurements - - * sunDirEst (mean value) - * magField (mean value) - * rmuSatRate (rmus, mean value) - * - Models to get inertia values - - * sunModelDir (input: time) - * magModelField (input: position,time) - * - Low Pass Filter maybe - - * magField - * SunDirEst*/ - class SensorProcessing { public: void reset(); @@ -50,7 +38,15 @@ class SensorProcessing { bool *magFieldModelValid, double *magneticFieldVectorDerivative, bool *magneticFieldVectorDerivativeValid); // Output - void processSus(acsctrl::SusDataRaw *susData, timeval timeOfSusMeasurement, + void processSus(const uint16_t *sus0Value, bool sus0valid, const uint16_t *sus1Value, + bool sus1valid, const uint16_t *sus2Value, bool sus2valid, + const uint16_t *sus3Value, bool sus3valid, const uint16_t *sus4Value, + bool sus4valid, const uint16_t *sus5Value, bool sus5valid, + const uint16_t *sus6Value, bool sus6valid, const uint16_t *sus7Value, + bool sus7valid, const uint16_t *sus8Value, bool sus8valid, + const uint16_t *sus9Value, bool sus9valid, const uint16_t *sus10Value, + bool sus10valid, const uint16_t *sus11Value, bool sus11valid, + timeval timeOfSusMeasurement, const AcsParameters::SusHandlingParameters *susParameters, const AcsParameters::SunModelParameters *sunModelParameters, double *sunDirEst, bool *sunDirEstValid, double *sunVectorInertial, bool *sunVectorInertialValid, diff --git a/mission/controller/acs/SensorValues.cpp b/mission/controller/acs/SensorValues.cpp index 11720aeb..9ca2b90b 100644 --- a/mission/controller/acs/SensorValues.cpp +++ b/mission/controller/acs/SensorValues.cpp @@ -5,30 +5,57 @@ * Author: rooob */ #include "SensorValues.h" -#include -#include + +#include #include +#include +#include + +#include namespace ACS { -SensorValues::SensorValues() { +SensorValues::SensorValues() {} + +SensorValues::~SensorValues() {} + +ReturnValue_t SensorValues::updateMgm() { + ReturnValue_t result; + PoolReadGuard pgMgm0(&mgm0Lis3Set), pgMgm1(&mgm1Rm3100Set), pgMgm2(&mgm2Lis3Set), + pgMgm3(&mgm3Rm3100Set), pgImtq(&imtqMgmSet); + + result = (pgMgm0.getReadResult() || pgMgm1.getReadResult() || pgMgm2.getReadResult() || + pgMgm3.getReadResult() || pgImtq.getReadResult()); + return result; } -SensorValues::~SensorValues() { +ReturnValue_t SensorValues::updateSus() { + ReturnValue_t result; + PoolReadGuard pgSus0(&susSets[0]), pgSus1(&susSets[1]), pgSus2(&susSets[2]), pgSus3(&susSets[3]), + pgSus4(&susSets[4]), pgSus5(&susSets[5]), pgSus6(&susSets[6]), pgSus7(&susSets[7]), + pgSus8(&susSets[8]), pgSus9(&susSets[9]), pgSus10(&susSets[10]), pgSus11(&susSets[11]); + + result = (pgSus0.getReadResult() || pgSus1.getReadResult() || pgSus2.getReadResult() || + pgSus3.getReadResult() || pgSus4.getReadResult() || pgSus5.getReadResult() || + pgSus6.getReadResult() || pgSus7.getReadResult() || pgSus8.getReadResult() || + pgSus9.getReadResult() || pgSus10.getReadResult() || pgSus11.getReadResult()); + return result; } ReturnValue_t SensorValues::update() { -// lp_var_t quaternion(objects::STAR_TRACKER, PoolIds::CALI_QW, nullptr, pool_rwm_t::VAR_READ); -// ReturnValue_t result = quaternion.read(); + updateSus(); + updateMgm(); -// if ( result != RETURN_OK) { -// return RETURN_FAILED; -// } -// quatJB[3] = static_cast(quaternion.value); -// quatJBValid = quaternion.isValid(); + // lp_var_t quaternion(objects::STAR_TRACKER, PoolIds::CALI_QW, nullptr, + // pool_rwm_t::VAR_READ); + // ReturnValue_t result = quaternion.read(); + // + // if (result != RETURN_OK) { + // return RETURN_FAILED; + // } + // quatJB[3] = static_cast(quaternion.value); + // quatJBValid = quaternion.isValid(); - return returnvalue::OK; + return returnvalue::OK; } -} - - +} // namespace ACS diff --git a/mission/controller/acs/SensorValues.h b/mission/controller/acs/SensorValues.h index 001b141b..daf4913c 100644 --- a/mission/controller/acs/SensorValues.h +++ b/mission/controller/acs/SensorValues.h @@ -1,99 +1,85 @@ -/* Created on: 08.03.2022 - * Author: Robin - */ - #ifndef SENSORVALUES_H_ #define SENSORVALUES_H_ -#include + +#include +#include "mission/devices/devicedefinitions/SusDefinitions.h" +#include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" +#include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" +#include "mission/devices/devicedefinitions/IMTQHandlerDefinitions.h" namespace ACS { class SensorValues{ -public: - SensorValues(); - virtual ~SensorValues(); + public: + SensorValues(); + virtual ~SensorValues(); - ReturnValue_t update(); + ReturnValue_t update(); + ReturnValue_t updateMgm(); + ReturnValue_t updateSus(); - float mgm0[3]; - float mgm1[3]; - float mgm2[3]; - float mgm3[3]; - float mgm4[3]; + MGMLIS3MDL::MgmPrimaryDataset mgm0Lis3Set = + MGMLIS3MDL::MgmPrimaryDataset(objects::MGM_0_LIS3_HANDLER); + RM3100::Rm3100PrimaryDataset mgm1Rm3100Set = + RM3100::Rm3100PrimaryDataset(objects::MGM_1_RM3100_HANDLER); + MGMLIS3MDL::MgmPrimaryDataset mgm2Lis3Set = + MGMLIS3MDL::MgmPrimaryDataset(objects::MGM_2_LIS3_HANDLER); + RM3100::Rm3100PrimaryDataset mgm3Rm3100Set = + RM3100::Rm3100PrimaryDataset(objects::MGM_3_RM3100_HANDLER); + IMTQ::RawMtmMeasurementSet imtqMgmSet = IMTQ::RawMtmMeasurementSet(objects::IMTQ_HANDLER); - bool mgm0Valid; - bool mgm1Valid; - bool mgm2Valid; - bool mgm3Valid; - bool mgm4Valid; + std::array susSets{ + SUS::SusDataset(objects::SUS_0_N_LOC_XFYFZM_PT_XF), + SUS::SusDataset(objects::SUS_1_N_LOC_XBYFZM_PT_XB), + SUS::SusDataset(objects::SUS_2_N_LOC_XFYBZB_PT_YB), + SUS::SusDataset(objects::SUS_3_N_LOC_XFYBZF_PT_YF), + SUS::SusDataset(objects::SUS_4_N_LOC_XMYFZF_PT_ZF), + SUS::SusDataset(objects::SUS_5_N_LOC_XFYMZB_PT_ZB), + SUS::SusDataset(objects::SUS_6_R_LOC_XFYBZM_PT_XF), + SUS::SusDataset(objects::SUS_7_R_LOC_XBYBZM_PT_XB), + SUS::SusDataset(objects::SUS_8_R_LOC_XBYBZB_PT_YB), + SUS::SusDataset(objects::SUS_9_R_LOC_XBYBZB_PT_YF), + SUS::SusDataset(objects::SUS_10_N_LOC_XMYBZF_PT_ZF), + SUS::SusDataset(objects::SUS_11_R_LOC_XBYMZB_PT_ZB), + }; - float sus0[3]; - float sus1[3]; - float sus2[3]; - float sus3[3]; - float sus4[3]; - float sus5[3]; - float sus6[3]; - float sus7[3]; - float sus8[3]; - float sus9[3]; - float sus10[3]; - float sus11[3]; + double rmu0[3]; + double rmu1[3]; + double rmu2[3]; - bool sus0Valid; - bool sus1Valid; - bool sus2Valid; - bool sus3Valid; - bool sus4Valid; - bool sus5Valid; - bool sus6Valid; - bool sus7Valid; - bool sus8Valid; - bool sus9Valid; - bool sus10Valid; - bool sus11Valid; + bool rmu0Valid; + bool rmu1Valid; + bool rmu2Valid; + double quatJB[4]; // output star tracker. quaternion or dcm ? refrence to which KOS? + bool quatJBValid; + int strIntTime[2]; - double rmu0[3]; - double rmu1[3]; - double rmu2[3]; + double gps0latitude; // Reference is WGS84, so this one will probably be geodetic + double gps0longitude; // Should be geocentric for IGRF + double gps0altitude; + double gps0Velocity[3]; // speed over ground = ?? + double gps0Time; // utc - bool rmu0Valid; - bool rmu1Valid; - bool rmu2Valid; + // valid ids for gps values ! + int gps0TimeYear; + int gps0TimeMonth; + int gps0TimeHour; // should be double + bool gps0Valid; - double quatJB[4]; // output star tracker. quaternion or dcm ? refrence to which KOS? - bool quatJBValid; - int strIntTime[2]; - - double gps0latitude; //Reference is WGS84, so this one will probably be geodetic - double gps0longitude; //Should be geocentric for IGRF - double gps0altitude; - double gps0Velocity[3]; // speed over ground = ?? - double gps0Time; //utc - -// valid ids for gps values ! - int gps0TimeYear; - int gps0TimeMonth; - int gps0TimeHour; // should be double - bool gps0Valid; - - - bool mgt0valid; - -// Reaction wheel measurements - double speedRw0; // RPM [1/min] - double speedRw1; // RPM [1/min] - double speedRw2; // RPM [1/min] - double speedRw3; // RPM [1/min] - bool validRw0; - bool validRw1; - bool validRw2; - bool validRw3; + bool mgt0valid; + // Reaction wheel measurements + double speedRw0; // RPM [1/min] + double speedRw1; // RPM [1/min] + double speedRw2; // RPM [1/min] + double speedRw3; // RPM [1/min] + bool validRw0; + bool validRw1; + bool validRw2; + bool validRw3; }; } /* namespace ACS */ #endif /*ENSORVALUES_H_*/ - diff --git a/mission/controller/acs/SusConverter.cpp b/mission/controller/acs/SusConverter.cpp index ea52f5a2..26804f12 100644 --- a/mission/controller/acs/SusConverter.cpp +++ b/mission/controller/acs/SusConverter.cpp @@ -14,30 +14,26 @@ #include -bool SusConverter::checkSunSensorData(lp_vec_t susChannel) { - if (susChannel.value[0] <= susChannelValueCheckLow || - susChannel.value[0] > susChannelValueCheckHigh || - susChannel.value[0] > susChannel.value[GNDREF]) { +bool SusConverter::checkSunSensorData(const uint16_t susChannel[6]) { + if (susChannel[0] <= susChannelValueCheckLow || susChannel[0] > susChannelValueCheckHigh || + susChannel[0] > susChannel[GNDREF]) { return false; } - if (susChannel.value[1] <= susChannelValueCheckLow || - susChannel.value[1] > susChannelValueCheckHigh || - susChannel.value[1] > susChannel.value[GNDREF]) { + if (susChannel[1] <= susChannelValueCheckLow || susChannel[1] > susChannelValueCheckHigh || + susChannel[1] > susChannel[GNDREF]) { return false; }; - if (susChannel.value[2] <= susChannelValueCheckLow || - susChannel.value[2] > susChannelValueCheckHigh || - susChannel.value[2] > susChannel.value[GNDREF]) { + if (susChannel[2] <= susChannelValueCheckLow || susChannel[2] > susChannelValueCheckHigh || + susChannel[2] > susChannel[GNDREF]) { return false; }; - if (susChannel.value[3] <= susChannelValueCheckLow || - susChannel.value[3] > susChannelValueCheckHigh || - susChannel.value[3] > susChannel.value[GNDREF]) { + if (susChannel[3] <= susChannelValueCheckLow || susChannel[3] > susChannelValueCheckHigh || + susChannel[3] > susChannel[GNDREF]) { return false; }; - susChannelValueSum = 4 * susChannel.value[GNDREF] - (susChannel.value[0] + susChannel.value[1] + - susChannel.value[2] + susChannel.value[3]); + susChannelValueSum = + 4 * susChannel[GNDREF] - (susChannel[0] + susChannel[1] + susChannel[2] + susChannel[3]); if ((susChannelValueSum < susChannelValueSumHigh) && (susChannelValueSum > susChannelValueSumLow)) { return false; @@ -45,17 +41,17 @@ bool SusConverter::checkSunSensorData(lp_vec_t susChannel) { return true; } -void SusConverter::calcAngle(lp_vec_t susChannel) { +void SusConverter::calcAngle(const uint16_t susChannel[6]) { float xout, yout; float s = 0.03; // s=[mm] gap between diodes uint8_t d = 5; // d=[mm] edge length of the quadratic aperture uint8_t h = 1; // h=[mm] distance between diodes and aperture int ch0, ch1, ch2, ch3; // Substract measurement values from GNDREF zero current threshold - ch0 = susChannel.value[GNDREF] - susChannel.value[0]; - ch1 = susChannel.value[GNDREF] - susChannel.value[1]; - ch2 = susChannel.value[GNDREF] - susChannel.value[2]; - ch3 = susChannel.value[GNDREF] - susChannel.value[3]; + ch0 = susChannel[GNDREF] - susChannel[0]; + ch1 = susChannel[GNDREF] - susChannel[1]; + ch2 = susChannel[GNDREF] - susChannel[2]; + ch3 = susChannel[GNDREF] - susChannel[3]; // Calculation of x and y xout = ((d - s) / 2) * (ch2 - ch3 - ch0 + ch1) / (ch0 + ch1 + ch2 + ch3); //[mm] @@ -124,11 +120,10 @@ float* SusConverter::calculateSunVector() { return sunVectorBodyFrame; } -float* SusConverter::getSunVectorSensorFrame(lp_vec_t susChannel, +float* SusConverter::getSunVectorSensorFrame(const uint16_t susChannel[6], const float coeffAlpha[9][10], const float coeffBeta[9][10]) { calcAngle(susChannel); calibration(coeffAlpha, coeffBeta); return calculateSunVector(); } - diff --git a/mission/controller/acs/SusConverter.h b/mission/controller/acs/SusConverter.h index 32f9e954..01143a39 100644 --- a/mission/controller/acs/SusConverter.h +++ b/mission/controller/acs/SusConverter.h @@ -17,16 +17,14 @@ class SusConverter { public: SusConverter() {} - bool checkSunSensorData(lp_vec_t susChannel); + bool checkSunSensorData(const uint16_t susChannel[6]); - void calcAngle(lp_vec_t susChannel); + void calcAngle(const uint16_t susChannel[6]); void calibration(const float coeffAlpha[9][10], const float coeffBeta[9][10]); float* calculateSunVector(); - bool getValidFlag(uint8_t susNumber); - float* getSunVectorSensorFrame(lp_vec_t susChannel, const float coeffAlpha[9][10], + float* getSunVectorSensorFrame(const uint16_t susChannel[6], const float coeffAlpha[9][10], const float coeffBeta[9][10]); - float* TransferSunVector(); private: float alphaBetaRaw[2]; //[°] -- 2.34.1 From c8d91dce7d31ef107efb44735b11e0c15f3eab2c Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 11 Oct 2022 14:56:18 +0200 Subject: [PATCH 048/101] format fix. added GYR orientation matrices --- mission/controller/acs/AcsParameters.h | 1734 +++++++++++------------- 1 file changed, 828 insertions(+), 906 deletions(-) diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 85ceaec0..29caa59e 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -6,947 +6,869 @@ #ifndef ACSPARAMETERS_H_ #define ACSPARAMETERS_H_ -#include #include +#include + typedef unsigned char uint8_t; -class AcsParameters /*: public HasParametersIF*/{ -public: +class AcsParameters /*: public HasParametersIF*/ { + public: + AcsParameters(); + virtual ~AcsParameters(); + /* + virtual ReturnValue_t getParameter(uint8_t domainId, uint16_t parameterId, + ParameterWrapper *parameterWrapper, + const ParameterWrapper *newValues, uint16_t startAtIndex); + */ + struct OnBoardParams { + double sampleTime = 0.1; // [s] + } onBoardParams; - AcsParameters(); - virtual ~AcsParameters(); -/* - virtual ReturnValue_t getParameter(uint8_t domainId, uint16_t parameterId, - ParameterWrapper *parameterWrapper, - const ParameterWrapper *newValues, uint16_t startAtIndex); -*/ - struct OnBoardParams { - double sampleTime = 0.1; // [s] - } onBoardParams; + struct InertiaEIVE { + double inertiaMatrix[3][3] = {{1.0, 0.0, 0.0}, {0.0, 1.0, 0.0}, {0.0, 0.5, 1.0}}; + double inertiaMatrixInverse[3][3]; + } inertiaEIVE; - struct InertiaEIVE { - double inertiaMatrix[3][3] = { - { 1.0, 0.0, 0.0}, - { 0.0, 1.0, 0.0}, - { 0.0, 0.5, 1.0}}; - double inertiaMatrixInverse[3][3]; - } inertiaEIVE; + struct MgmHandlingParameters { + float mgm0orientationMatrix[3][3] = {{0, 0, -1}, {0, 1, 0}, {1, 0, 0}}; + float mgm1orientationMatrix[3][3] = {{0, 0, 1}, {0, -1, 0}, {1, 0, 0}}; + float mgm2orientationMatrix[3][3] = {{0, 0, -1}, {0, 1, 0}, {1, 0, 0}}; + float mgm3orientationMatrix[3][3] = {{0, 0, 1}, {0, -1, 0}, {1, 0, 0}}; + float mgm4orientationMatrix[3][3] = {{0, 0, -1}, {-1, 0, 0}, {0, 1, 0}}; + } mgmHandlingParameters; - struct MgmHandlingParameters { - float mgm0orientationMatrix[3][3] = { - { 0, 0,-1}, - { 0, 1, 0}, - { 1, 0, 0}}; - float mgm1orientationMatrix[3][3] = { - { 0, 0, 1}, - { 0,-1, 0}, - { 1, 0, 0}}; - float mgm2orientationMatrix[3][3] = { - { 0, 0,-1}, - { 0, 1, 0}, - { 1 ,0, 0}}; - float mgm3orientationMatrix[3][3] = { - { 0, 0, 1}, - { 0,-1, 0}, - { 1, 0, 0}}; - float mgm4orientationMatrix[3][3] = { - { 0, 0,-1}, - {-1, 0, 0}, - { 0, 1, 0}}; - } mgmHandlingParameters; + struct SusHandlingParameters { + float sus0orientationMatrix[3][3] = {{0, 0, 1}, {1, 0, 0}, {0, 1, 0}}; // FM07 + float sus1orientationMatrix[3][3] = {{0, 0, -1}, {-1, 0, 0}, {0, 1, 0}}; // FM06 + float sus2orientationMatrix[3][3] = {{-1, 0, 0}, {0, 0, -1}, {0, -1, 0}}; // FM13 + float sus3orientationMatrix[3][3] = {{1, 0, 0}, {0, 0, 1}, {0, -1, 0}}; // FM14 + float sus4orientationMatrix[3][3] = {{0, -1, 0}, {1, 0, 0}, {0, 0, 1}}; // FM05 + float sus5orientationMatrix[3][3] = {{1, 0, 0}, {0, -1, 0}, {0, 0, -1}}; // FM02 + float sus6orientationMatrix[3][3] = {{0, 0, 1}, {1, 0, 0}, {0, 1, 0}}; // FM10 + float sus7orientationMatrix[3][3] = {{0, 0, -1}, {-1, 0, 0}, {0, 1, 0}}; // FM01 + float sus8orientationMatrix[3][3] = {{-1, 0, 0}, {0, 0, -1}, {0, -1, 0}}; // FM03 + float sus9orientationMatrix[3][3] = {{1, 0, 0}, {0, 0, 1}, {0, -1, 0}}; // FM11 + float sus10orientationMatrix[3][3] = {{0, -1, 0}, {1, 0, 0}, {0, 0, 1}}; // FM09 + float sus11orientationMatrix[3][3] = {{1, 0, 0}, {0, -1, 0}, {0, 0, -1}}; // FM08 - struct SusHandlingParameters { - float sus0orientationMatrix[3][3] = { - { 0, 0, 1}, - { 1, 0, 0}, - { 0, 1, 0}}; // FM07 - float sus1orientationMatrix[3][3] = { - { 0, 0,-1}, - {-1, 0, 0}, - { 0, 1, 0}}; // FM06 - float sus2orientationMatrix[3][3] = { - {-1, 0, 0}, - { 0, 0,-1}, - { 0,-1, 0}}; // FM13 - float sus3orientationMatrix[3][3] = { - { 1, 0, 0}, - { 0, 0, 1}, - { 0,-1, 0}}; // FM14 - float sus4orientationMatrix[3][3] = { - { 0,-1, 0}, - { 1, 0, 0}, - { 0, 0, 1}}; // FM05 - float sus5orientationMatrix[3][3] = { - { 1, 0, 0}, - { 0,-1, 0}, - { 0, 0,-1}}; // FM02 - float sus6orientationMatrix[3][3] = { - { 0, 0, 1}, - { 1, 0, 0}, - { 0, 1, 0}}; // FM10 - float sus7orientationMatrix[3][3] = { - { 0, 0,-1}, - {-1, 0, 0}, - { 0, 1, 0}}; // FM01 - float sus8orientationMatrix[3][3] = { - {-1, 0, 0}, - { 0, 0,-1}, - { 0,-1, 0}}; // FM03 - float sus9orientationMatrix[3][3] = { - { 1, 0, 0}, - { 0, 0, 1}, - { 0,-1, 0}}; // FM11 - float sus10orientationMatrix[3][3] = { - { 0,-1, 0}, - { 1, 0, 0}, - { 0, 0, 1}}; // FM09 - float sus11orientationMatrix[3][3] = { - { 1, 0, 0}, - { 0,-1, 0}, - { 0, 0,-1}}; // FM08 + float sus0coeffAlpha[9][10] = { + {10.4400948050067, 1.38202655603079, 0.975299591736672, 0.0172133914423707, + -0.0163482459492803, 0.035730152619911, 0.00021725657060767, -0.000181685375645396, + -0.000124096561459262, 0.00040790566176981}, + {6.38281281805793, 1.81388255990089, 0.28679524291736, 0.0218036823758417, + 0.010516766426651, 0.000446101708841615, 0.00020187044149361, 0.000114957457831415, + 1.63114413539632e-05, -2.0187452317724e-05}, + {-29.3049094555, -0.506844002611835, 1.64911970541112, -0.0336282997119334, + 0.053185806861685, -0.028164943139695, -0.00021098074590512, 0.000643681643489995, + -0.000249094601806692, 0.000231466668650876}, + {-4.76233790255328, 1.1780710601961, -0.194257188545164, 0.00471817228628384, + -0.00183773644319332, -0.00570261621182479, -7.99203367291902e-05, 7.75752247926601e-05, + -9.78534772816957e-06, -4.72083745991256e-05}, + {0.692159025649028, 1.11895461388667, 0.341706834956496, 0.000237989648019541, + -0.000188322779563912, 0.000227310789253953, 0.000133001646828401, -0.000305810826248463, + 0.00010150571088124, -0.000367705461590854}, + {3.38094203317731, 1.24778838596815, 0.067807236112956, -0.00379395536123526, + -0.00339180589343601, -0.00188754615986649, -7.52406312245606e-05, 4.58398750278147e-05, + 6.97244631313601e-05, 2.50519145070895e-05}, + {-7.10546287716029, 0.459472977452686, -1.12251049944014, 0.0175406972371191, + -0.0310525406867782, -0.0531315970690727, -0.000121107664597462, 0.000544665437051928, + -1.78466217018177e-05, -0.00058976234038192}, + {1.60633684055984, 1.1975095485662, 0.180159204664965, -0.00259157601062089, + -0.0038106317634397, 0.000956686555225968, 4.28416721502134e-06, 5.84532336259517e-06, + -2.73407888222758e-05, 5.45131881032866e-06}, + {43.3732235586222, 0.528096786861784, -3.41255850703983, -0.0161629934278675, + 0.0790998053536612, 0.0743822668655928, 0.000237176965460634, -0.000426691336904078, + -0.000889196131314391, -0.000509766491897672}}; + float sus0coeffBeta[9][10] = { + {1.03872648284911, -0.213507239271552, 1.43193059498181, -0.000972717820830235, + -0.00661046096415371, 0.00974284211491888, 2.96098456891215e-05, -8.2933115634257e-05, + -5.52178824394723e-06, 5.73935295303589e-05}, + {3.42242235823356, 0.0848392511283237, 1.24574390342586, 0.00356248195980133, + 0.00100415659893053, -0.00460120247716139, 3.84891005422427e-05, 2.70236417852327e-05, + -7.58501977656551e-05, -8.79809730730992e-05}, + {14.0092526123741, 1.03126714946215, 1.0611008563785, 0.04076462444523, 0.0114106419194518, + 0.00746959159048058, 0.000388033225774727, -0.000124645014888926, -0.000296639947532341, + -0.00020861690864945}, + {1.3562422681189, -0.241585615891602, 1.49170424068611, 0.000179184170448335, + -0.00712399257616284, 0.0121433526723498, 3.29770580642447e-05, 8.78960210966787e-06, + -6.00508568552101e-05, 0.000101583822589461}, + {-0.718855428908583, -0.344067476078684, 1.12397093701762, 0.000236505431484729, + -0.000406441415248947, 0.00032834991502413, 0.000359422093285086, 8.18895560425272e-05, + 0.000316835483508523, 0.000151442890664899}, + {-0.268764016434841, -0.275272048639511, 1.26239753050527, -0.000511224336925231, + 0.0095628568270856, -0.00397960092451418, 1.39587366293607e-05, 1.31409051361129e-05, + -9.83662017231755e-05, 1.87078667116619e-05}, + {27.168106989145, -2.43346872338192, 1.91135512970771, 0.0553180826818016, + -0.0481878292619383, 0.0052773235604729, -0.000428011927975304, 0.000528018208222772, + -0.000285438191474895, -5.71327627917386e-05}, + {-0.169494136517622, -0.350851545482921, 1.19922076033643, 0.0101120903675328, + -0.00151674465424115, 0.00548694086125656, -0.000108240000970513, 1.57202185024105e-05, + -9.77555098179959e-05, 2.09624089449761e-05}, + {-32.3807957489507, 1.8271436443167, 2.51530814328123, -0.0532334586403461, + -0.0355980127727253, -0.0213373892796204, 0.00045506092539885, 0.000545065581027688, + 0.000141998709314758, 0.000101051304611037}}; + float sus1coeffAlpha[9][10] = { + {-27.6783250420482, -0.964805032861791, -0.503974297997131, -0.0446471081874084, + -0.048219538329297, 0.000958491361905381, -0.000290972187162876, -0.000657145721554176, + -0.000178087038629721, 4.09208968678946e-05}, + {2.24803085641869, 1.42938692406645, 0.30104994020693, 0.00756499999397385, + 0.0117765927439368, -0.000743685980641362, 4.69920803836194e-05, 0.000129815636957956, + -9.10792250542345e-06, -2.03870119873411e-05}, + {26.9943033817917, 0.147791175366868, -3.48256070200564, -0.0303332422478656, + 0.0183377266255394, 0.124593616125966, -0.000466003049304431, -0.000272000698791331, + -0.00063621309529853, -0.00158363678978767}, + {-0.221893380318465, 1.29919955307083, 0.21872487901019, 0.0049448219667127, + 0.00291224091529189, 0.00654651987282984, -9.86842469311185e-05, 8.20057454706638e-05, + 6.42331081725944e-05, 7.11656918299053e-05}, + {1.40178843964621, 1.1733111455249, 0.287485528779234, -0.000793970428759834, + 0.000170529273905818, -0.00268807864923086, 9.09553964483881e-05, -0.000271892733575409, + 8.52016306311741e-05, -0.000291797625433646}, + {0.65549617899457, 1.25716478394514, 0.301396415134214, -0.00357289640403958, + -0.000473416364133431, -0.010760332636205, -9.77220176481185e-05, 4.40798040046875e-05, + 2.84958344955681e-05, 0.000128583400693359}, + {6.20958048145025, 1.9528406481596, 1.32915657614139, -0.0326944423378284, + -0.0158258335207969, 0.0328249756354635, 0.00027113042931131, -0.000133980867173428, + -0.000357964552318811, 0.000224235061786191}, + {2.46222812180944, 1.1731834908026, 0.17440330925151, -0.00132279581980401, + -0.00447202005426964, -0.000804321602550913, -1.59526570766446e-05, 2.62946483533391e-05, + 3.28466749016414e-05, -6.63837547601294e-06}, + {42.615758859473, 2.46617281707273, -5.742515881283, -0.131942799763164, 0.20250702826603, + 0.0981562802911027, 0.00189939440077981, -0.0018591621618441, -0.00161121179693977, + -0.00058814458116749}}; + float sus1coeffBeta[9][10] = { + {-12.300032617206, -1.06640894101328, 0.33950802247214, -0.00890867870617722, + -0.04872758086642, -0.0114263851027856, 0.000141061196404012, -0.000675469545483099, + -0.000138249928781575, -0.000138871036200597}, + {10.1631114109768, 0.261654603839785, 1.2376413405181, 0.00888558138614535, + 0.00151674939001532, -0.00534577602313027, 9.19430013005559e-05, 5.39804599087081e-05, + -4.15760162347772e-05, -7.60797902457032e-05}, + {-30.142329062199, 1.26939195100229, 6.14467186367471, 0.0464163689935328, + 0.00379001947505376, -0.165444163648109, 0.000516545385538741, 1.56053219154647e-05, + -5.58651971370719e-05, 0.00173185063955313}, + {12.1454103989862, -0.243589095509132, 2.02543716988677, -0.000857989774598331, + -0.00705278543432513, 0.0250580538307654, 3.50683653081847e-05, -2.63093897408875e-05, + -5.67352645830913e-05, 0.000232270832022029}, + {4.4338108906594, -0.305276965994378, 1.17293558142526, 0.000152618994429577, + 0.00134432642920902, -0.00104036813342885, 0.000334476082056995, 6.74826804343671e-05, + 0.000275311897725414, 7.58157740577916e-05}, + {3.47680700379043, -0.154163381023597, 1.389579838768, 0.000799705880026268, + 0.00401980026462874, -0.00915311817354667, -2.54817301605075e-06, -2.27422984169921e-05, + -2.61224817848938e-05, 6.00381132540332e-05}, + {29.469181543703, -0.722888948550437, 3.3623377135197, 0.00148445490093232, + -0.0474780142430845, 0.0486755575785462, 0.000126295091963757, 0.000526632230895258, + -0.000259305985126003, 0.000412751148048724}, + {2.67029041722834, -0.0837968038501666, 1.37628504937018, 0.00165061312885753, + -0.00953813055064273, 0.0032433005486936, -1.6522452172598e-05, 0.000144574078261271, + -8.47348746872376e-05, -1.92509604512729e-06}, + {-20.959201441285, -2.23605897639125, 5.73044624806043, 0.0354141964763815, + 0.0887545371234514, -0.193862330062381, 0.000216532998121618, -0.00207707610520973, + 0.000552928905346826, 0.00190182163597828}}; + float sus2coeffAlpha[9][10] = { + {6.51602979328333, 0.690575501042577, 1.18185457002269, -0.0153161662266588, + 0.00145972227341484, 0.0351496474730776, -0.000172645571366945, -6.04213053580018e-05, + 9.74494676304114e-05, 0.000334122888261002}, + {0.954398509323963, 1.10996214782069, 0.313314231563221, -0.00367553051112208, + 0.0110290193380194, 0.000240079475656232, -6.93444423181303e-05, 0.000107433381295167, + 1.30750132315838e-05, -2.43580795300515e-05}, + {-55.1159841655056, -1.47449655191106, 3.40106264596874, -0.0621428271456258, + 0.0659788065633613, -0.0791732068323335, -0.000524264070592741, 0.000582093651418709, + -0.000586102213707195, 0.000658133691098817}, + {1.98614148820353, 1.32058724763677, 0.156843003413303, 0.002748082456053, + 0.00202677073171519, 0.00382360695862248, -0.000122364309010211, 5.33354637965168e-05, + 3.93641210098335e-05, 4.06398431916703e-05}, + {3.41223117010734, 1.1597568029329, 0.31881674291653, -0.000382400010917784, + -0.000754945672515052, -0.00079200882313927, 0.000145713118224563, -0.00026910957285589, + 0.000137876961532787, -0.000326798596746712}, + {6.23333031852853, 1.24902998148103, -0.0162317540018123, -0.00338184464699201, + 0.000420329743164687, 0.00202038442335185, -7.10435889754986e-05, -6.04039458988991e-06, + 7.25318569569788e-06, -2.5930447720704e-05}, + {191.759784636909, -10.5228276216193, 8.48306234734519, 0.243240262512846, + -0.344226468125615, 0.126267158197535, -0.00186612281541009, 0.00304415728817747, + -0.00304958575196089, 0.000457236034569107}, + {5.61375025356727, 1.1692295110657, 0.224665256727786, -0.00230481633344849, + -0.00746693012026367, -0.00172583925345173, -7.00823444553058e-06, 7.31362778266959e-05, + 5.81988007269583e-05, 1.3723604109425e-05}, + {98.0250669452855, -2.18500123986039, -6.68238707939385, 0.000754807832106659, + 0.256133336978808, 0.110826583415768, 0.000457663127670018, -0.00197655629847616, + -0.00254305206375073, -0.000466731538082995}}; + float sus2coeffBeta[9][10] = { + {41.1102358678699, 2.3034699186519, 2.74551448799899, 0.061701310929235, 0.0317074142089495, + 0.0308171492962288, 0.00049453042200054, 0.000519222896270701, 2.85420168881716e-05, + 0.000259197384126413}, + {4.46821725251333, 0.0125273331991983, 1.32640678842532, 0.000543566569079156, + 0.00396616601484022, -0.00488408099728387, -3.05734704054868e-06, 7.3424831303621e-05, + -5.49439160235527e-05, -8.30708110469922e-05}, + {64.773396165255, 2.97057686090134, -1.90770757709096, 0.062747116236773, + -0.077990648565002, 0.0613989204238974, 0.00055512113297293, -0.000347045533958329, + 0.00104059576098392, -0.000348638726253297}, + {3.10352939390402, -0.2376108554276, 1.60523925160222, 0.00116454605680723, + -0.0067958260462381, 0.0136561370875238, 2.59929059167486e-05, 3.33825895937897e-05, + -5.55828531601728e-05, 0.000109833374761172}, + {0.156052891975873, -0.320721597024578, 1.15208488414874, 0.00164743688819939, + 0.000534718891498932, 0.000469870758457642, 0.000308432468885207, 0.00011789470679678, + 0.000292373398965513, 0.000183599033441813}, + {2.84967971406268, -0.21374251183113, 1.09938586447269, 2.34894704600407e-05, + 0.00588345375399262, 0.00296966835738407, 8.42707308834155e-06, 2.81870099202641e-06, + -3.56732787246631e-05, -7.04534663356379e-05}, + {-7.59892007483895, 0.358662160515702, 0.805137646978357, 0.00222144376998348, + 0.0464438387809707, 0.00847551828841782, 3.24805702347551e-05, 5.45500807838332e-05, + 0.000941378089367713, 0.000353137737023192}, + {-4.65367165487109, 0.201306010390421, 1.19135575710523, -0.00692801521395975, + 0.00394118754078443, 0.00426360093528599, 6.297683536736e-05, -7.15794236895102e-05, + -7.47076172176468e-05, -1.94516917836346e-05}, + {-59.5882618930651, 3.84530212586425, 3.50497032358686, -0.116100453177197, + -0.0380997421813177, -0.0581898335691109, 0.00111464935006159, 0.000559313074537689, + 0.000168067749764069, 0.000563224178849256}}; + float sus3coeffAlpha[9][10] = { + {-174.687021034355, -7.53454036765748, -9.33798316371397, -0.18212338430986, + -0.242523652239734, -0.202086838965846, -0.00138648793335223, -0.00225430176012882, + -0.00198887215340364, -0.00160678535160774}, + {6.92009692410602, 1.8192037428209, 0.254908171908415, 0.0179273243472017, + 0.00894059238779664, -0.000436952529644, 0.000138070523903458, 9.22759645920339e-05, + -9.4312261303588e-06, -1.76647897892869e-05}, + {-17.9720006944368, 0.230510201259892, 1.10751755772907, -0.00973621304161327, + 0.0554450499198677, -0.00590970792122449, -2.92393772526592e-05, 0.000444329929586969, + -0.000436055839773919, -9.5869891049503e-05}, + {-4.9880829382985, 1.33627775121504, -0.330382157073243, 0.00306744056311184, + 0.00376353074674973, -0.0107453978169225, -0.00010680477021693, 5.17225535432745e-05, + 7.4423443938376e-05, -0.000107927900087035}, + {0.952867982900728, 1.14513280899596, 0.307744203675505, 0.000404669974219378, + -0.000737988606997615, 0.00120218232577844, 0.000191147653645603, -0.000275058867995882, + 0.000137187356620739, -0.000320202731145004}, + {8.076706574364, 1.31338618710295, -0.334634356394277, -0.00209719438033295, + -0.00381753503582303, 0.0100347823323616, -7.00550548221671e-05, -1.97626956996069e-05, + 7.80079707003333e-05, -8.95904360920744e-05}, + {-82.4748312650249, 8.63074484663009, -0.949295700187556, -0.178618807265278, + 0.130143669167547, 0.0284326533865768, 0.00149831261351137, -0.0011583692969717, + 0.0010560778729661, 0.000635404380970666}, + {3.34457857521978, 1.09242517408071, 0.241722402244944, 0.00381629887587041, + -0.00863580122530851, 0.00137050492069702, -8.91046701171713e-05, 8.44169683308007e-05, + -3.54608413548779e-05, 8.54042677832451e-06}, + {78.1540457908649, -1.30266922193303, -5.33605443700115, 0.0184226131926499, + 0.146629920899062, 0.110698519952472, 6.64041537651749e-05, -0.00120174584530713, + -0.00133177694921411, -0.000796422644338886}}; + float sus3coeffBeta[9][10] = { + {-31.5704266802979, -5.10700699133189, 2.84549700473812, -0.122701561048957, + -0.11257100034746, 0.102120576206517, -0.000796645106694696, -0.00192211266325167, + -4.99981232866237e-05, 0.00104036677004523}, + {-0.734294938181273, -0.0694317595592039, 1.34746975389878, -0.00103465544451119, + 0.00389798465946559, -0.00308561832194191, -2.91843250099708e-06, 7.59634622232999e-05, + -6.54571602919161e-05, -0.000104146832644606}, + {24.2649069708536, 3.08145095664586, 1.88975821636026, 0.0767528234206466, + -0.0526971951753399, -0.0477053831942802, 0.000613806533422364, -0.000631628059238499, + 0.00026217621127941, 0.000555307997961608}, + {0.62884078560034, -0.152668817824194, 1.70304497205574, 0.000894387499536142, + -0.00306495168098874, 0.0180087418010658, 1.74990847586174e-05, 3.1263263531046e-05, + -7.1643235604579e-06, 0.000147876621100347}, + {-3.05400297018165, -0.316256447664344, 1.14841722699638, 0.000671621084688467, + -0.000906765726598906, 0.000687041032077189, 0.000323419818039841, 0.000128019308781935, + 0.000286018723737538, 0.000192248693306256}, + {-4.39855066935163, -0.322858945262125, 1.44405016355615, -4.93181749911261e-05, + 0.0127396834052722, -0.00523149676786941, 2.56561922352657e-05, 7.61202764874326e-06, + -0.00014623717850039, 8.12219846932013e-06}, + {110.820397525173, -10.9497307382094, 2.48939759290446, 0.296585618718034, + -0.142611297893517, -0.0141810186612052, -0.00275127095595919, 0.00160686698368569, + -0.000872029428758877, -0.000410522437887563}, + {-7.15740446281205, 0.104233532313688, 1.13155893729292, -0.00350418544400852, + 0.00532058598508803, 0.00459314980222008, 3.09155436939349e-05, -7.60935741692174e-05, + -5.87922606348196e-05, 2.56146268588382e-05}, + {44.8818060495112, -7.94729992210875, 3.59286389225051, 0.217944601088562, + 0.108087933176612, -0.116711715153385, -0.00194260120960441, -0.0015752762498594, + -0.000331129410732722, 0.00125896996438418}}; + float sus4coeffAlpha[9][10] = { + {-12.4581187126738, 0.398038572289047, -0.438887880988151, -0.00965382887938283, + -0.0309322349328842, -0.00359106522420111, -7.79546112299913e-06, -0.000432733997178497, + -9.79031907635314e-05, -1.49299384451257e-05}, + {8.41054378583447, 1.87462327360707, 0.266809999719952, 0.0216455385250676, + 0.00879426079919981, -0.00142295319820553, 0.000194819780653264, 8.57549705064449e-05, + -3.56478452552367e-05, -1.65680920554434e-05}, + {16.4141780945815, 2.57697842088604, 0.373972171754278, 0.0498264199400303, + 0.0183175817756131, -0.008545409848878, 0.000422696533006382, -0.000268245978898508, + -0.000663188021815416, -7.51144017137827e-05}, + {0.796692054977593, 1.26773229735266, 0.247715261673662, 0.00358183885438128, + 0.00216435175662881, 0.00713732829335305, -0.000110129715615857, 3.56051594182427e-05, + 5.03074365340535e-05, 8.40279146176271e-05}, + {2.37491588500165, 1.05997969088519, 0.309540461340971, -0.000405047711742513, + 0.000462224730316111, -0.00201887171945793, 0.000260159805167265, -0.000282867209803598, + 0.000201613303652666, -0.000277796442847579}, + {6.36749007598708, 1.31659760017973, -0.122724934153231, -0.00328808937096891, + -0.00577347207798776, 0.00403172074457999, -7.45676459772001e-05, 1.79838644222274e-05, + 0.000104552066440564, -2.78115121929346e-05}, + {-47.9667098848496, 3.97703197139796, -1.96403894754299, -0.0577989657406978, + 0.0634225576208007, -0.0346023445055141, 0.00045886475369098, -0.000326132951996844, + 0.000716490441845967, -0.000136132038635483}, + {6.21505474256094, 0.871830486201601, 0.286906473833627, 0.007875292606045, + -0.00974634725746389, 0.00128416935792136, -0.000111796743751489, 0.000102016719989187, + -3.3503088289589e-05, -1.03874407813931e-05}, + {102.09801265482, -4.12715152309748, -5.04594403360339, 0.075499959116996, + 0.216574192561683, 0.0750031215784663, -0.000147358932612646, -0.0023710703422108, + -0.00143310719642393, -0.000431914403446768}}; + float sus4coeffBeta[9][10] = { + {-21.5077132684032, -1.60004839699939, -0.0298995033958561, -0.0315563250430659, + -0.0424403625879891, -0.0245426225510417, -0.000209861203016225, -0.000422150973104431, + -0.00030514398458781, -0.000211986731019738}, + {9.07644247897601, 0.207457289788099, 1.26735366597312, 0.00768477352180427, + 0.00429230749575816, -0.00514802326062087, 7.56149591998578e-05, 8.42794730840662e-05, + -3.62215715492783e-05, -5.24384190165239e-05}, + {-33.5225408043693, -3.11167857248829, 1.91760591695775, -0.0963752386435729, + 0.00026620241534153, -0.0256680391021823, -0.00102188712837393, 2.63753563968978e-05, + 0.000113172463974702, 0.000271939918507175}, + {19.1379025029401, -0.225979661987912, 2.72337120022998, -0.00136982412154458, + -0.00447301210555274, 0.046496718064139, 2.09123846958985e-05, -4.30383094864847e-05, + -1.22808643520768e-05, 0.000440555709696048}, + {2.957867714783, -0.316069593806939, 1.06379930645214, 0.00103244713047271, + 0.00148059212230411, 0.000557885068990542, 0.000288633931072557, 0.000172775380291659, + 0.000269738457990237, 0.000254577019084984}, + {2.04155199929521, -0.318303488378033, 1.37820715117028, 0.00114788656817743, + 0.0130051117909245, -0.00743109928493789, 1.22403390396844e-05, -3.19245785131217e-05, + -0.000156735218010879, 3.81458400945988e-05}, + {27.314954181241, -1.43916155634084, 2.48967706992348, 0.0278695408478388, + -0.0341141456915131, 0.0281959785297513, -0.000252996164135396, 0.000163365679366542, + -0.000380129463154642, 0.000159350154429114}, + {-0.274693278266294, 0.0199711721436635, 1.26676843352524, -0.0006713759238817, + -0.00389715205101059, 0.00294298337610857, -9.58643121413979e-06, 6.30700938550725e-05, + -6.07188867796123e-05, 7.72199861279611e-06}, + {-74.1601853968901, 2.55641628908672, 6.38533530714782, -0.0582345132980647, + -0.0653804553172819, -0.138850555683872, 0.000489364157827405, 0.000469559629292745, + 0.000698140692952438, 0.00123017528239406}}; + float sus5coeffAlpha[9][10] = { + {-12.1398741236355, 1.99425442858125, -1.9303044815802, 0.0418421279520049, + -0.0309683799946315, -0.0562201123081437, 0.000522607299552916, -0.000375386573815007, + -0.000183899715035788, -0.000600349486293698}, + {4.51862054729553, 1.72396080253297, 0.274562680698765, 0.0162681383591035, + 0.0108410181586673, -0.000272215427359511, 0.000124164068046579, 0.000125586897851351, + -1.24082224214974e-05, -1.63339067540159e-05}, + {63.0100748193658, 7.78014670478172, 0.327263471268564, 0.181264302704374, + -0.0652454854214506, -0.03906716801285, 0.00166924078925478, -0.000749939315526625, + 0.000320696101132374, 0.000499934751180042}, + {-2.14377722994325, 1.33617641673436, 0.0973465660282871, 0.00389526886867845, + 0.00526064997381395, 0.00244964888333519, -8.59416490903541e-05, 4.58871931007681e-05, + 8.6123353128647e-05, 2.85447259858337e-05}, + {0.164792977301912, 1.17541977248641, 0.348838798760518, -0.000180865118417534, + 0.000331789515553421, -0.000734333865631793, 9.76677859410759e-05, -0.000324347075049525, + 8.66683396011167e-05, -0.000385839566009832}, + {-0.228934187493575, 1.30552820143752, 0.306779576899158, -0.00508763741184706, + -0.00318524263093038, -0.00878095392529144, -6.59040013073836e-05, 8.69122529321691e-05, + 5.73853071731283e-05, 8.56628414466758e-05}, + {22.6047744510684, -0.591739857860868, 0.566728856847393, 0.0498124268150265, + -0.0214126910277926, 0.00538091942017912, -0.000391517685229849, 0.000554321668236216, + 0.000191004410219065, 0.000102775124022018}, + {4.54704081104052, 0.844841244606025, 0.181355971462193, 0.0109743851006749, + -0.00363467884122547, 0.00108873046814694, -0.000153236888951059, 3.14623342713789e-06, + -2.78503202185463e-05, 3.99983788680736e-06}, + {-30.878359404848, 5.20536009886854, -0.674455093700773, -0.10801865891189, + -0.0514805639475938, 0.0503660452068572, 0.00072776817295273, 0.00120288537038655, + -0.000301602375634166, -0.000477098479809266}}; + float sus5coeffBeta[9][10] = { + {16.8155737032787, 0.65475660868259, 1.95532810363711, 0.000295624718662669, + 0.0426379914736747, 0.00192544771588337, -4.94534888281508e-05, 8.32299142575155e-05, + 0.000645497238623369, -0.000234155227840799}, + {9.48268090632318, 0.528942263930744, 1.34030963800712, 0.0173605129814363, + 0.00581086655972212, -0.00365006277801141, 0.000180048140973223, 0.000102002650672644, + -4.10833110241736e-05, -8.7810396165556e-05}, + {-47.8325489165383, -4.78262055949503, 1.66912859871505, -0.143518014673292, + 0.0288441527062856, -0.00322823115861497, -0.00148509910480755, 0.000284265179004289, + -0.000175299737313045, -7.04175618676909e-05}, + {3.70510151312723, -0.272200626024415, 1.5527519845099, 0.000589727630962265, + -0.00889682554869096, 0.0109857452472628, 3.05876215574877e-05, 2.09194236165814e-05, + -8.33769024439277e-05, 6.90991113575066e-05}, + {0.820199776906695, -0.355683467192776, 1.17142130858009, -0.000160174871610729, + 4.09723480153701e-05, 0.000209103751629257, 0.000390331989170637, 6.45642836249667e-05, + 0.000318092703362044, 0.000107158633760141}, + {5.52084497768914, -0.227775345312466, 0.845897282556327, 0.00157426476122436, + 0.00657189797805861, 0.0103797665963117, 2.51479848048895e-05, -4.78371400399983e-05, + -5.20221896473413e-05, -0.000143840492906166}, + {-33.4875689683454, 0.937557276329106, -1.02741065470967, -0.0140023273976314, + 0.0401908729477037, -0.0512457211360142, 7.05537967426573e-05, -0.00027521752411122, + 0.000407657552700476, -0.000458411000693613}, + {0.931346887326171, -0.320804452025793, 1.28866325376154, 0.00912456151698805, + -0.00404367403569981, 0.00477543659981282, -9.43987917474817e-05, 4.66464249533497e-05, + -7.89362487264572e-05, -1.0951496495443e-05}, + {-38.3689359928435, 3.8540516906071, 1.26391725545116, -0.108584643500539, + -0.0542697403292778, 0.0285360568428252, 0.000845084580479371, 0.00114184315411245, + -0.000169538153750085, -0.000336529204350355}}; + float sus6coeffAlpha[9][10] = { + {13.0465222152293, 0.0639132159808454, 2.98083557560227, -0.0773202212713293, + 0.0949075412003712, 0.0503055998355815, -0.00104133434256204, 0.000633099036136146, + 0.00091428505258307, 0.000259857066722932}, + {1.66740227859888, 1.55804368674744, 0.209274741749388, 0.0123798418560859, + 0.00724950517167516, -0.000577445375457582, 8.94374551545955e-05, 6.94513586221567e-05, + -1.06065583714065e-05, -1.43899892666699e-05}, + {8.71610925597519, 1.42112818752419, -0.549859300501301, 0.0374581774684577, + 0.0617635595955198, 0.0447491072679598, 0.00069998577106559, 0.00101018723225412, + -4.88501228194031e-06, -0.000434861113274231}, + {-2.3555601314395, 1.29430213886389, 0.179499593411187, 0.00440896450927253, + 0.00352052300927628, 0.00434187143967281, -9.66615195654703e-05, 3.64923075694275e-05, + 6.09619017310129e-05, 4.23908862836885e-05}, + {-0.858019663974047, 1.10138705956076, 0.278789852526915, -0.000199798507752607, + 0.00112092406838628, -0.00177346866231588, 0.000217816070307086, -0.000240713988238257, + 0.000150795563555828, -0.000279246491927943}, + {7.93661480471297, 1.33902098855997, -0.64010306493848, -0.00307944184518557, + -0.00511421127083497, 0.0204008636376403, -9.50042323904954e-05, 6.01530207062221e-05, + 9.13233708460098e-05, -0.000206717750924323}, + {16.2658124154565, 0.191301571705827, 1.02390350838635, 0.0258487436355216, + -0.0219752092833362, 0.0236916776412211, -0.000350496453661261, -0.000123849795280597, + -0.000532190902882765, 9.36018171121253e-05}, + {-1.53023612303052, 1.29132951637076, 0.181159073530008, -0.0023490608317645, + -0.00370741703297037, -0.000229071300377431, -1.6634455407558e-05, 1.11387154630828e-05, + 1.02609175615251e-05, -9.64717658954667e-06}, + {-32.9918791079688, 0.093536793089853, 4.76858627395571, 0.0595845684553358, + -0.054845749101257, -0.133247382500001, -0.000688999201915199, 7.67286265747961e-05, + 0.000868163357631254, 0.00120099606910313}}; + float sus6coeffBeta[9][10] = { + {12.7380220453847, -0.6087309901836, 2.60957722462363, -0.0415319939920917, + 0.0444944768824276, 0.0223231464060241, -0.000421503508733887, -9.39560038638717e-05, + 0.000821479971871302, -4.5330528329465e-05}, + {1.96846333975847, -0.33921438143463, 1.23957110477613, -0.00948832495296823, + 0.00107211134687287, -0.00410820045700199, -9.33679611473279e-05, 3.72984782145427e-05, + -4.04514487800062e-05, -7.6296149087237e-05}, + {5.7454444934481, -1.58476383793609, -0.418479494289251, -0.0985177320630941, + -0.0862179276808015, 0.0126762052037897, -0.00118207758271301, -0.000190361442918412, + 0.0011723869613426, 0.000122882034141316}, + {2.11042287406433, -0.225942746245056, 1.18084080712528, -0.00103013931607172, + -0.00675606790663387, -0.00106646109062746, 1.7708839355979e-05, -3.13642668374253e-05, + -5.87601932564404e-05, -3.92033314627704e-05}, + {2.96049248725882, -0.286261455028255, 1.09122556181319, -0.000672369023155898, + 0.000574446975796023, 0.000120303729680796, 0.000292285799270644, 0.000170497873487264, + 0.000259925974231328, 0.000222437797823852}, + {1.65218061201483, -0.19535446105784, 1.39609640918411, 0.000961524354787167, + 0.00592400381724333, -0.0078500192096718, -7.02791628080906e-07, -2.07197580883822e-05, + -4.33518182614169e-05, 4.66993119419691e-05}, + {-19.56673237415, 1.06558565338761, 0.151160448373445, -0.0252628659378108, + 0.0281230551050938, -0.0217328869907185, 0.000241309440918385, -0.000116449585258429, + 0.000401546410974577, -0.000147563886502726}, + {1.56167171538684, -0.155299366654736, 1.20084049723279, 0.00457348893890231, + 0.00118888040006052, 0.0029920178735941, -5.583448120596e-05, -2.34496315691865e-05, + -5.3309466243918e-05, 6.20289310356821e-06}, + {1.95050549495182, -2.74909818412705, 3.80268788018641, 0.0629242254381785, + 0.0581479035315726, -0.111361283351269, -0.00047845777495158, -0.00075354297736741, + -0.000186887396585446, 0.00119710704771344}}; + float sus7coeffAlpha[9][10] = { + {-92.1126183408754, -3.77261746189525, -4.50604668349213, -0.0909560776043523, + -0.15646903318971, -0.0766293642415356, -0.00059452135473577, -0.00144790037129283, + -0.00119021101127241, -0.000460110780350978}, + {1.60822506792345, 1.12993931449931, 0.300781032865641, -0.00405149856360946, + 0.0116663280665617, -0.000746071920075153, -8.36092173253351e-05, 0.000126762041147563, + -1.57820750462019e-05, -2.13840141586661e-05}, + {-151.403952985468, -5.77049222793992, 9.71132757422642, -0.113259116970462, + 0.284142453949027, -0.198625061659164, -0.000836450164210354, 0.00174062771509636, + -0.00323746390757859, 0.00124721932086258}, + {3.47391964888809, 1.28788318973591, 0.358380140281919, 0.0033863520864927, + 0.00154601909793475, 0.0103457296050314, -9.56426572270873e-05, 5.48838958555808e-05, + 2.97537427220847e-05, 0.000104735911514185}, + {3.32650947866065, 1.16701012685798, 0.293514063672376, -0.00065850791542434, + -8.61746510464303e-05, -0.00212038990772211, 0.00010377123197, -0.000262818127593837, + 0.000103360882478383, -0.000296739688930329}, + {-0.440176043435378, 1.18923278867097, 0.519516382652818, -0.00138846714677511, + 0.00266491699926247, -0.014254675949624, -4.20279929822439e-05, -5.49260281515447e-05, + -1.00328708454487e-05, 0.000138142092498215}, + {9.54962966738358, 1.83809145920811, 1.82162819067959, -0.0116786627338505, + -0.00496037444422313, 0.0590883547819332, 7.48465315787857e-05, 0.000221693951602584, + 7.96466345174136e-06, 0.000638822537725177}, + {7.04862901290925, 0.876813777672465, 0.16368093989381, 0.00928717461441627, + -0.00276538956293246, 0.00117995419940653, -0.000141511492474493, -6.09796031786385e-06, + -2.62114930414747e-05, -2.88713611443788e-06}, + {135.349147631811, -7.21933296299596, -6.02379024934871, 0.19557354282067, + 0.207680233512614, 0.12880101618361, -0.00169832076532024, -0.00192216719797732, + -0.00188763612041332, -0.00103101801961442}}; + float sus7coeffBeta[9][10] = { + {-12.7115487367622, -1.08890790360556, 0.0579616268854079, -0.0212303293514951, + -0.0395948453851818, -0.0275564242614342, -0.000228652851842222, -0.000148106159109458, + -0.000555136649469199, -0.000198260004582737}, + {-0.988147625946871, -0.759018567468546, 1.20998292002818, -0.0241231836977845, + -0.000572110443300516, -0.00294835038249426, -0.00026533039022186, 6.82250069765274e-06, + 7.21038415209318e-06, -6.54881435118179e-05}, + {98.0979345921564, 4.27381413621355, -4.39956005193548, 0.0709109587666745, + -0.172774236139236, 0.107243391488741, 0.000421832640471043, -0.00140450884710288, + 0.00158019019392239, -0.00078512547169536}, + {4.10892685652543, -0.229301778557857, 1.33380992987117, -0.000250095848720304, + -0.00555205065514645, 0.00355052914398176, 1.62727119770752e-05, -1.26026527654764e-05, + -3.25505031810898e-05, 5.79970895921158e-06}, + {3.09432502337258, -0.300556003790433, 1.17085811008124, 0.00128679594824324, + 0.00148229981422985, 9.15267474159147e-05, 0.000300497843413856, 6.31378865575566e-05, + 0.000258447032558814, 9.79142983264352e-05}, + {8.92336134924575, -0.197306981784312, 0.659908505354084, 0.00175572239373996, + 0.006801023678097, 0.0189775987436792, 9.2187857727721e-06, -4.8706332690626e-05, + -6.887009887486e-05, -0.000266455617735054}, + {-52.0734887320227, 2.64822385560272, -1.72387600304694, -0.0383944891609251, + 0.110873671161269, -0.0475247245070445, 0.000194652401328063, -0.000697307928990137, + 0.00124021816001, -0.000194213899980878}, + {2.08203985879155, -0.127503525368396, 1.17628056094647, 0.00283288065938444, + 0.00394668214608305, 0.00314868636161131, -2.99504350569853e-05, -7.11070816314279e-05, + -6.30148122529749e-05, 2.28114298989664e-05}, + {191.321181158032, -12.2449557187473, -7.21933741885107, 0.267954293388644, + 0.331529493933124, 0.149867703984027, -0.00222279201444128, -0.00284724570619954, + -0.00298774060233964, -0.000988903783752156}}; + float sus8coeffAlpha[9][10] = { + {5.46354311880959, 1.15370126035432, 0.568432485840475, -0.00105094692478431, + -0.000472899673842554, 0.015581320536192, 2.26460844314248e-05, -0.000254397947062058, + 0.000198938007250408, 0.000102026690279006}, + {8.8976133108173, 1.89502416095352, 0.268670471819199, 0.0217013413241972, + 0.00973925295182384, -0.00116357269193765, 0.000185865842232419, 0.000103311614912702, + -2.46539447920969e-05, -2.06292928734686e-05}, + {-45.4550803910752, 1.27220123406993, 5.21483855848504, 0.0315791081623634, + 0.0725172355124129, -0.13947591535243, 0.000412577580637848, 0.000434545096994917, + -0.000840043932292312, 0.00126857487044307}, + {1.81302768546433, 1.20563501267535, 0.344815267182167, 0.00546879453241056, + -0.00115382996865884, 0.010597876132341, -7.75885604486581e-05, 8.99568815949154e-05, + -2.98129544974679e-06, 0.000108913239345604}, + {2.19111439539173, 1.06951675598148, 0.283707798607213, 0.00016478588207518, + 0.000196086067268121, -0.00214980231173703, 0.000237820475654357, -0.000256402967908595, + 0.000165966620658577, -0.000268394081675921}, + {15.0858674915897, 1.27922724811168, -1.0803137812576, -0.00184009775302466, + -0.00458792284209219, 0.0359393555418547, -6.05121024079603e-05, -1.2288384024143e-05, + 8.55484605384438e-05, -0.000379241348638065}, + {-14.9594190080906, 1.79473182195746, -1.00830704063572, 0.000890685410857856, + 0.0408932029176081, -0.0165460857151619, -0.000170544299916973, -0.000370901607010145, + 0.000324089709129097, -9.33010240878062e-05}, + {0.867614491733251, 1.38248194737027, 0.233408537422123, -0.00772942878114575, + -0.00783126068079782, -0.000413713955432221, 4.5775750146291e-05, 6.97323029940275e-05, + 1.70664456940787e-05, 6.75517901233086e-06}, + {2.34474364146174, -0.777275400251477, 2.09531381577911, 0.0170780716714389, + 0.102855060371092, -0.1203441505925, 0.000187004964420911, -0.00141720441050986, + -0.000336251285258365, 0.00145175125888695}}; + float sus8coeffBeta[9][10] = { + {28.3033101237397, 1.77504446792811, 1.70758838986317, 0.0307800697044683, + 0.0598759344275936, -0.014461432284373, 0.000128415617799076, 0.000664419128546701, + 0.000312923304130995, -0.000269026446641855}, + {7.73040563051023, 0.0267291479555493, 1.16189582308493, 0.000611047892976521, + -0.00213680506915073, -0.00517435586596902, -3.60304406049766e-06, -1.74452976404459e-05, + -3.95396925228538e-05, -7.01948519410633e-05}, + {-48.0766126130725, -3.77981206700298, 3.03482861087335, -0.0678496412519532, + 0.115260678424016, -0.0109681510065038, -0.000438011443691466, 0.00097230136258486, + -0.000930875177732769, -0.000203144239955507}, + {12.1881935626341, -0.234345089308583, 2.01134619426134, 0.000181529284001169, + -0.00642848065105061, 0.0243985799415726, 2.0224042581776e-05, 5.22503286757285e-06, + -4.75196303016323e-05, 0.000221160482364556}, + {3.49559433498742, -0.294995112674766, 1.07892379698257, 0.000861664794052587, + 0.00138978933062055, 0.000436385106465176, 0.000288095124755908, 0.000147259769247883, + 0.000256686898599516, 0.000198982412957039}, + {9.36663996178607, -0.171266136751803, 0.799869891484541, -0.000896305696610864, + 0.00477919972789653, 0.0077876110326094, 9.16475263625076e-06, 3.02461250100473e-05, + -3.63917701783264e-05, -0.000101376940843402}, + {9.93372683055145, 1.02056557854246, 3.01635426591734, -0.0477113881140277, + -0.0280426434406976, 0.0438813017696874, 0.000470431190169998, -7.55753674679743e-05, + -0.000516444906323815, 0.000253844418223843}, + {4.12868774589741, -0.305711790187688, 1.15739216407191, 0.00942395115281056, + 0.00264758462357433, 0.00227985850688479, -0.000107537164019682, -4.91396736189963e-05, + -5.3803493814502e-05, 6.80587059728718e-06}, + {64.9193383444005, -1.57724255547465, -3.82166532626293, 0.0104712238987591, + 0.0898786950946473, 0.128910456296131, -8.27123227422217e-05, -0.000143979624107479, + -0.00146684876653306, -0.00102226799570239}}; + float sus9coeffAlpha[9][10] = { + {65.8975109449121, 2.19115342242175, 6.11069527811832, -0.0219884864133703, + 0.119985456538482, 0.142746712551924, -0.000465882328687976, 0.000606525132125852, + 0.00141667074621881, 0.00109715845894006}, + {5.70337356029945, 1.86705636976809, 0.235584190291708, 0.0194937327615426, + 0.00973291465247784, -0.00155675297510773, 0.000147099297988423, 0.000115708967219349, + -4.1462310493722e-05, -9.80097031103588e-06}, + {138.221145997284, 6.07665575619595, -9.08085914250542, 0.0839801072927519, + -0.143071750033303, 0.237868300719915, 0.000626693630444932, -0.000579788170871402, + 0.00181740650944343, -0.00207086879728281}, + {-7.78295582666151, 1.37506685179192, -0.507596181420042, 0.00350118305456038, + 0.00380814310115541, -0.0174012437563343, -0.000124801268056815, 2.96314830184492e-05, + 6.3416992450033e-05, -0.000190177262510221}, + {0.13102597129751, 1.24228303845143, 0.328808873447393, 2.6858679536165e-05, + 0.000231428138164498, -0.000584089095259736, 5.5322167970451e-05, -0.000322205709821716, + 7.71348293209208e-05, -0.000393885990364776}, + {4.64571633968935, 1.2668223691397, -0.158952088650432, -0.0038344859267428, + 0.0030051503726095, 0.00455578826025588, -9.42520993914957e-05, 5.81633314412289e-05, + -4.43545804544095e-05, -4.83524454851519e-05}, + {99.2385930314563, -3.65569343617926, 5.54203926675588, 0.0975630395981933, + -0.15701634159692, 0.107834711298836, -0.000885326636237814, 0.000960753844480462, + -0.00179894024848343, 0.000583066757644971}, + {2.82671549736619, 1.11214198870501, 0.214735318432744, 0.00284415167563662, + -0.00743289575690122, 0.000382705440762292, -7.43232442872501e-05, 6.96994098083348e-05, + -4.15108111710131e-06, 1.33520085213482e-05}, + {36.9013743125415, -0.522392401546163, -1.52452843963663, 0.0261375433218879, + 0.060573568610239, 0.0182582125221054, -0.000244373383911157, -0.000271385147292484, + -0.000723799969427732, 6.76324880239196e-05}}; + float sus9coeffBeta[9][10] = { + {128.70886435409, 7.27355509732751, 7.18142203531244, 0.1536100459329, 0.199455846541636, + 0.101824964939793, 0.00116666116789421, 0.00181595584079788, 0.00159271319494017, + 0.000556768406475719}, + {-7.07933839681024, -0.979062424441878, 1.21792546815617, -0.0295740143783226, + -0.00442780611714201, -0.00329612819203176, -0.000291373125216143, -7.47259350176359e-05, + -4.87265282482212e-05, -7.87490350444332e-05}, + {41.1357193180502, 2.75138456414254, -0.0160889117718198, 0.0274001112562423, + -0.145644717742057, -0.0316076203283094, -0.000136443337244472, -0.00153945199081365, + 0.000938960439977633, 0.000599987111822885}, + {2.7980384746608, -0.234741037383589, 1.5342193016705, -0.000993791566721689, + -0.00787533639513478, 0.00927468655141365, 2.63308697896639e-05, -3.42816267184975e-05, + -8.48879419798771e-05, 3.84043821333798e-05}, + {0.427687530667804, -0.346076633694936, 1.22968527483851, -4.95098138311122e-05, + 0.000298245372198029, 0.000332756250024796, 0.00040375986210644, 5.20675972504572e-05, + 0.000327042170278218, 5.93011568264671e-05}, + {4.50337810133314, -0.279364254817202, 0.945812187846199, 0.000116182663432306, + 0.0115646046622083, 0.00908289960302886, 1.90394667311541e-05, -4.4360223646434e-06, + -0.000131398914898614, -0.000145568992865512}, + {-36.3377213654193, 2.21047221783626, 0.0609982245149821, -0.0670546774988572, + 0.016827777144747, -0.0277834084058314, 0.000778301409125556, 0.000135846745194401, + 0.00043261858797068, -0.00021172728254561}, + {-0.737678205841529, -0.217352122193475, 1.23494846329297, 0.00748173441779792, + 0.0019595873704705, 0.00567253723266176, -8.34768773292938e-05, -3.50608394184873e-05, + -0.000107500091550635, -5.1379722947632e-07}, + {-36.6150844777671, 3.24952006904945, 1.7222457840185, -0.0846362445435584, + -0.0625549615377418, 0.019178365782485, 0.000664877496455304, 0.000942971403881222, + 0.000190754698755098, -0.000372226659190439}}; + float sus10coeffAlpha[9][10] = { + {14.4562393748324, 0.669162330324919, 2.13895255446541, -0.0161997097021299, + 0.00185995785065838, 0.0621351118528379, -0.000278999272493087, 0.000238469666491965, + -0.000279407497782961, 0.000726904943739837}, + {-4.45678285887022, 0.92869611919737, 0.186752102727282, -0.00706160758952316, + 0.00532680276723634, -0.00119102617674229, -0.000105283880098953, 3.90673052334419e-05, + -3.13338277344246e-05, 5.32977236959767e-06}, + {30.4255268053197, 3.00991076401191, -1.4855621363519, 0.033934286288413, + -0.0553588742704929, 0.0299275582316466, 0.000167915322354466, -0.00050925078118232, + 0.000463662961330962, -0.000232919143454163}, + {2.45076465343337, 1.30206564388838, 0.635121046212765, 0.00517109639797675, + 0.00360579544364496, 0.0198490668911362, -9.31556816982662e-05, 6.7313653707875e-05, + 6.4669137025142e-05, 0.000209727581169138}, + {-0.784841314851562, 1.10058314980836, 0.314063830836532, 0.000583003703415889, + 0.000312635453606579, -0.000183738114552387, 0.000214096205760617, -0.000286744686021244, + 0.000159157597180407, -0.00032235099420715}, + {7.19568036510586, 1.33307479701657, -0.465585141952456, -0.0031910726544199, + -0.00546273504371797, 0.0145494754402526, -7.9863949693769e-05, 4.83681329120104e-05, + 8.85844309936609e-05, -0.000143217870916994}, + {-12.8344546267449, 1.36023633150143, -0.728527724854506, 0.019982118403416, + 0.0385056413989437, -0.00468598272326268, -0.000303957957649245, -6.37783846968216e-05, + 0.000514049116643205, 0.000112015427600697}, + {-2.58279031298065, 1.42167821629586, 0.208769467511292, -0.00640190372145885, + -0.0056405289717473, 0.000509611313918708, 2.23310562107823e-05, 3.23685469522147e-05, + -7.55982776243849e-06, 2.78417756661088e-06}, + {-29.7178996143914, 2.636972251183, 1.97316329325243, -0.03983524158327, + -0.0193152048730234, -0.0600902798379509, 0.00031786916010672, 0.000162178988605602, + 0.000224550786416246, 0.000614337977361927}}; + float sus10coeffBeta[9][10] = { + {12.4771349792459, 1.44317849705414, 0.975637226331561, 0.0430284146301043, + 0.0220810531548995, -0.0220926906772, 0.000310052324529521, 0.000658151808869523, + -0.000288026365111098, -0.000214619731807045}, + {-0.113203260140131, -0.272424061092191, 1.27704377191184, -0.00791746619331075, + 0.00278646694862191, -0.00398881099259934, -8.09569694307212e-05, 5.99617384829016e-05, + -5.4550919751855e-05, -8.6314530565085e-05}, + {-48.585664295448, -2.04899787231903, 4.48757129623549, -0.0226180460431321, + 0.090326735447661, -0.0722998813632622, -6.77623771415477e-05, 0.000562585419036509, + -0.000956171370931993, 0.000491554402311223}, + {-1.20986884955482, -0.215604107185474, 1.22123198786617, 0.000256508527822089, + -0.00625056735692847, 0.00262961582224303, 2.27433984698861e-05, 1.60471509861372e-05, + -4.85061736834262e-05, -1.8387092782907e-06}, + {-0.250205907903409, -0.315819331560782, 1.09018364376391, -0.000521787614293089, + -0.000500747760913489, 2.48184307342838e-05, 0.000313799238640988, 0.000136669146368744, + 0.000278914324565192, 0.000218512838469476}, + {-1.38512578184076, -0.240456589364121, 1.34170304231345, 0.00017499230372669, + 0.0070862275911073, -0.00460640844814105, 1.27594111036696e-05, -4.73855624902052e-06, + -5.41141037812903e-05, 8.50767021818388e-06}, + {58.9917559342216, -2.28705697628345, 5.35995190407842, 0.0214721399750612, + -0.112195722921667, 0.0890150265857542, -0.000100675657768708, 0.000493488022135339, + -0.00137672908303878, 0.000518683157694955}, + {3.18905073365834, -0.633376549706314, 1.17190259811174, 0.0188817945597344, + 0.00107470708915782, 0.00400880471375267, -0.000197312295539118, -2.46543035998379e-05, + -6.07871064300252e-05, 1.91822310311955e-05}, + {-21.6881499304099, -0.563186103920008, 3.70747028664292, 0.021112883967427, + -0.00650020689049325, -0.0778533644688476, -0.000131921888670268, -0.000402754836445439, + 0.000551249824375055, 0.00062236627391337}}; + float sus11coeffAlpha[9][10] = { + {-5.23569698615548, -1.45500092391928, 2.7643243644756, -0.0762912296128707, + -0.0201645929971608, 0.0997226845779083, -0.000741669441569556, -0.000485368004931528, + 0.000166230212359982, 0.00103455037278067}, + {-7.7405077383712, 0.892040861541276, 0.39014957203484, -0.00952030929935314, + 0.0185577462685363, 0.000500600568760257, -0.000151227821554572, 0.000245334737283439, + 1.89380065823205e-05, 1.83481122973969e-07}, + {-27.462143709831, -1.68192474287299, 0.689411302961069, -0.0146021086710062, + 0.227153492753605, 0.0815806579791421, 2.92919049429149e-05, 0.00153760357651792, + -0.00247865821192621, -0.00166333309739387}, + {-6.74664748624368, 1.43279156053015, 0.0212787292914553, 0.00764792230365732, + 0.00796410301290615, 0.0014384998868733, -8.95239151813685e-05, 9.55245417090909e-05, + 0.000127251739461239, 3.26943341606363e-05}, + {-2.20391533717674, 1.32902400478083, 0.38633027011889, 0.00104660852197061, + 0.00105228824412283, -0.00242067551428214, -6.98346290136652e-05, -0.000369075232184835, + -1.59510520000704e-05, -0.000448565104826966}, + {-5.29476778147188, 1.4549556336236, 0.561334186252557, -0.00260896342687109, + -0.00855934179001141, -0.0182515354646452, -8.79385828606048e-05, 5.98357681659175e-05, + 0.000146570207542509, 0.000201596912834554}, + {-45.7906613832612, 3.77630104475902, -1.67494598155515, -0.0545433897761635, + 0.047897938410221, -0.0355687158405231, 0.000374738707508583, -0.000448453494537518, + 0.000377784972619365, -0.000276573228333836}, + {-9.11681182090372, 2.06933872940742, 0.26131496122122, -0.0259534033367855, + -0.00777266937872862, -0.00262135395843891, 0.000223790782655445, 6.40488537928934e-05, + 7.75581514100296e-05, -9.25934285039627e-06}, + {183.243883340634, -8.02281039502717, -10.0756951652703, 0.168750521462303, + 0.314006821405967, 0.200264755034566, -0.0011895153717447, -0.00253812476819896, + -0.00291324393641628, -0.00140062522117514}}; + float sus11coeffBeta[9][10] = { + {34.4499366074013, -0.438583698052091, 4.72111001451028, -0.041810050989433, + 0.0562461093661426, 0.0856849892524893, -0.000477813051406167, -3.16404257494464e-05, + 0.00102633196865105, 0.000552974013759876}, + {7.6366298088699, 0.150314752958302, 1.31364679484924, 0.00557696667395871, + 0.00163731860604376, -0.00454759608980269, 5.83979683674572e-05, 4.45944881220665e-05, + -4.27874746147066e-05, -8.77418673597557e-05}, + {130.156215011893, 1.85759000444524, -10.986892391833, -0.00686275191260681, + -0.188837138116058, 0.346177462085361, -0.000183276946352264, -0.000702183496893294, + 0.00293145272693857, -0.00318194442670715}, + {-1.67854820161036, -0.358899332859806, 0.956690839640595, -4.93862910503803e-05, + -0.0136134783014874, -0.00848731301504507, 3.75950499927045e-05, 1.35374694383289e-06, + -0.000156596507890443, -0.000123254220377897}, + {3.67569209537767, -0.387260959713287, 1.31343215605952, -0.00206444615206506, + 0.00145334813110285, -0.00151259497696238, 0.000449492568365603, 6.95883968949488e-07, + 0.000368585523744765, -6.3420715525635e-05}, + {14.3296323024886, -0.182979476956897, 0.306817119309235, -0.00022212115978293, + 0.00463485302909649, 0.0277574953550035, 1.1422454625565e-05, 1.06053257479502e-05, + -2.05720000720608e-05, -0.000338584671430337}, + {-18.7534921817754, 1.14272710923224, 0.460498062012866, -0.00995826989278202, + 0.0658502318647112, 0.00616942819937029, -7.70857153768402e-05, -0.000641755741925561, + 0.00047849204592989, 0.000158509018296766}, + {1.26543621388607, -0.176674379740481, 1.38814920935488, 0.00545485262295305, + -0.00499775616702264, 0.0038057039142173, -6.59604252054511e-05, 6.40211116049053e-05, + -6.74778593434431e-05, -2.81973589469059e-05}, + {116.975421945286, -5.53022680362263, -5.61081660666997, 0.109754904982136, + 0.167666815691513, 0.163137400730063, -0.000609874123906977, -0.00205336098697513, + -0.000889232196185857, -0.00168429567131815}}; - float sus0coeffAlpha[9][10] = { - {10.4400948050067, 1.38202655603079, 0.975299591736672, 0.0172133914423707, -0.0163482459492803, - 0.035730152619911, 0.00021725657060767, -0.000181685375645396, -0.000124096561459262, - 0.00040790566176981}, - {6.38281281805793, 1.81388255990089, 0.28679524291736, 0.0218036823758417, 0.010516766426651, - 0.000446101708841615, 0.00020187044149361, 0.000114957457831415, 1.63114413539632e-05, - -2.0187452317724e-05}, - {-29.3049094555, -0.506844002611835, 1.64911970541112, -0.0336282997119334, 0.053185806861685, - -0.028164943139695, -0.00021098074590512, 0.000643681643489995, -0.000249094601806692, - 0.000231466668650876}, - {-4.76233790255328, 1.1780710601961, -0.194257188545164, 0.00471817228628384, - -0.00183773644319332, -0.00570261621182479, -7.99203367291902e-05, 7.75752247926601e-05, - -9.78534772816957e-06, -4.72083745991256e-05}, - {0.692159025649028, 1.11895461388667, 0.341706834956496, 0.000237989648019541, - -0.000188322779563912, 0.000227310789253953, 0.000133001646828401, -0.000305810826248463, - 0.00010150571088124, -0.000367705461590854}, - {3.38094203317731, 1.24778838596815, 0.067807236112956, -0.00379395536123526, - -0.00339180589343601, -0.00188754615986649, -7.52406312245606e-05, 4.58398750278147e-05, - 6.97244631313601e-05, 2.50519145070895e-05}, - {-7.10546287716029, 0.459472977452686, -1.12251049944014, 0.0175406972371191, - -0.0310525406867782, -0.0531315970690727, -0.000121107664597462, 0.000544665437051928, - -1.78466217018177e-05, -0.00058976234038192}, - {1.60633684055984, 1.1975095485662, 0.180159204664965, -0.00259157601062089, - -0.0038106317634397, 0.000956686555225968, 4.28416721502134e-06, 5.84532336259517e-06, - -2.73407888222758e-05, 5.45131881032866e-06}, - {43.3732235586222, 0.528096786861784, -3.41255850703983, -0.0161629934278675, - 0.0790998053536612, 0.0743822668655928, 0.000237176965460634, -0.000426691336904078, - -0.000889196131314391, -0.000509766491897672}}; - float sus0coeffBeta[9][10] = { - {1.03872648284911, -0.213507239271552, 1.43193059498181, -0.000972717820830235, - -0.00661046096415371, 0.00974284211491888, 2.96098456891215e-05, -8.2933115634257e-05, - -5.52178824394723e-06, 5.73935295303589e-05}, - {3.42242235823356, 0.0848392511283237, 1.24574390342586, 0.00356248195980133, - 0.00100415659893053, -0.00460120247716139, 3.84891005422427e-05, 2.70236417852327e-05, - -7.58501977656551e-05, -8.79809730730992e-05}, - {14.0092526123741, 1.03126714946215, 1.0611008563785, 0.04076462444523, 0.0114106419194518, - 0.00746959159048058, 0.000388033225774727, -0.000124645014888926, -0.000296639947532341, - -0.00020861690864945}, - {1.3562422681189, -0.241585615891602, 1.49170424068611, 0.000179184170448335, - -0.00712399257616284, 0.0121433526723498, 3.29770580642447e-05, 8.78960210966787e-06, - -6.00508568552101e-05, 0.000101583822589461}, - {-0.718855428908583, -0.344067476078684, 1.12397093701762, 0.000236505431484729, - -0.000406441415248947, 0.00032834991502413, 0.000359422093285086, 8.18895560425272e-05, - 0.000316835483508523, 0.000151442890664899}, - {-0.268764016434841, -0.275272048639511, 1.26239753050527, -0.000511224336925231, - 0.0095628568270856, -0.00397960092451418, 1.39587366293607e-05, 1.31409051361129e-05, - -9.83662017231755e-05, 1.87078667116619e-05}, - {27.168106989145, -2.43346872338192, 1.91135512970771, 0.0553180826818016, -0.0481878292619383, - 0.0052773235604729, -0.000428011927975304, 0.000528018208222772, -0.000285438191474895, - -5.71327627917386e-05}, - {-0.169494136517622, -0.350851545482921, 1.19922076033643, 0.0101120903675328, - -0.00151674465424115, 0.00548694086125656, -0.000108240000970513, 1.57202185024105e-05, - -9.77555098179959e-05, 2.09624089449761e-05}, - {-32.3807957489507, 1.8271436443167, 2.51530814328123, -0.0532334586403461, -0.0355980127727253, - -0.0213373892796204, 0.00045506092539885, 0.000545065581027688, 0.000141998709314758, - 0.000101051304611037}}; - float sus1coeffAlpha[9][10] = { - {-27.6783250420482, -0.964805032861791, -0.503974297997131, -0.0446471081874084, - -0.048219538329297, 0.000958491361905381, -0.000290972187162876, -0.000657145721554176, - -0.000178087038629721, 4.09208968678946e-05}, - {2.24803085641869, 1.42938692406645, 0.30104994020693, 0.00756499999397385, 0.0117765927439368, - -0.000743685980641362, 4.69920803836194e-05, 0.000129815636957956, -9.10792250542345e-06, - -2.03870119873411e-05}, - {26.9943033817917, 0.147791175366868, -3.48256070200564, -0.0303332422478656, - 0.0183377266255394, 0.124593616125966, -0.000466003049304431, -0.000272000698791331, - -0.00063621309529853, -0.00158363678978767}, - {-0.221893380318465, 1.29919955307083, 0.21872487901019, 0.0049448219667127, - 0.00291224091529189, 0.00654651987282984, -9.86842469311185e-05, 8.20057454706638e-05, - 6.42331081725944e-05, 7.11656918299053e-05}, - {1.40178843964621, 1.1733111455249, 0.287485528779234, -0.000793970428759834, - 0.000170529273905818, -0.00268807864923086, 9.09553964483881e-05, -0.000271892733575409, - 8.52016306311741e-05, -0.000291797625433646}, - {0.65549617899457, 1.25716478394514, 0.301396415134214, -0.00357289640403958, - -0.000473416364133431, -0.010760332636205, -9.77220176481185e-05, 4.40798040046875e-05, - 2.84958344955681e-05, 0.000128583400693359}, - {6.20958048145025, 1.9528406481596, 1.32915657614139, -0.0326944423378284, -0.0158258335207969, - 0.0328249756354635, 0.00027113042931131, -0.000133980867173428, -0.000357964552318811, - 0.000224235061786191}, - {2.46222812180944, 1.1731834908026, 0.17440330925151, -0.00132279581980401, - -0.00447202005426964, -0.000804321602550913, -1.59526570766446e-05, 2.62946483533391e-05, - 3.28466749016414e-05, -6.63837547601294e-06}, - {42.615758859473, 2.46617281707273, -5.742515881283, -0.131942799763164, 0.20250702826603, - 0.0981562802911027, 0.00189939440077981, -0.0018591621618441, -0.00161121179693977, - -0.00058814458116749}}; - float sus1coeffBeta[9][10] = { - {-12.300032617206, -1.06640894101328, 0.33950802247214, -0.00890867870617722, -0.04872758086642, - -0.0114263851027856, 0.000141061196404012, -0.000675469545483099, -0.000138249928781575, - -0.000138871036200597}, - {10.1631114109768, 0.261654603839785, 1.2376413405181, 0.00888558138614535, 0.00151674939001532, - -0.00534577602313027, 9.19430013005559e-05, 5.39804599087081e-05, -4.15760162347772e-05, - -7.60797902457032e-05}, - {-30.142329062199, 1.26939195100229, 6.14467186367471, 0.0464163689935328, 0.00379001947505376, - -0.165444163648109, 0.000516545385538741, 1.56053219154647e-05, -5.58651971370719e-05, - 0.00173185063955313}, - {12.1454103989862, -0.243589095509132, 2.02543716988677, -0.000857989774598331, - -0.00705278543432513, 0.0250580538307654, 3.50683653081847e-05, -2.63093897408875e-05, - -5.67352645830913e-05, 0.000232270832022029}, - {4.4338108906594, -0.305276965994378, 1.17293558142526, 0.000152618994429577, - 0.00134432642920902, -0.00104036813342885, 0.000334476082056995, 6.74826804343671e-05, - 0.000275311897725414, 7.58157740577916e-05}, - {3.47680700379043, -0.154163381023597, 1.389579838768, 0.000799705880026268, - 0.00401980026462874, -0.00915311817354667, -2.54817301605075e-06, -2.27422984169921e-05, - -2.61224817848938e-05, 6.00381132540332e-05}, - {29.469181543703, -0.722888948550437, 3.3623377135197, 0.00148445490093232, -0.0474780142430845, - 0.0486755575785462, 0.000126295091963757, 0.000526632230895258, -0.000259305985126003, - 0.000412751148048724}, - {2.67029041722834, -0.0837968038501666, 1.37628504937018, 0.00165061312885753, - -0.00953813055064273, 0.0032433005486936, -1.6522452172598e-05, 0.000144574078261271, - -8.47348746872376e-05, -1.92509604512729e-06}, - {-20.959201441285, -2.23605897639125, 5.73044624806043, 0.0354141964763815, 0.0887545371234514, - -0.193862330062381, 0.000216532998121618, -0.00207707610520973, 0.000552928905346826, - 0.00190182163597828}}; - float sus2coeffAlpha[9][10] = { - {6.51602979328333, 0.690575501042577, 1.18185457002269, -0.0153161662266588, - 0.00145972227341484, 0.0351496474730776, -0.000172645571366945, -6.04213053580018e-05, - 9.74494676304114e-05, 0.000334122888261002}, - {0.954398509323963, 1.10996214782069, 0.313314231563221, -0.00367553051112208, - 0.0110290193380194, 0.000240079475656232, -6.93444423181303e-05, 0.000107433381295167, - 1.30750132315838e-05, -2.43580795300515e-05}, - {-55.1159841655056, -1.47449655191106, 3.40106264596874, -0.0621428271456258, - 0.0659788065633613, -0.0791732068323335, -0.000524264070592741, 0.000582093651418709, - -0.000586102213707195, 0.000658133691098817}, - {1.98614148820353, 1.32058724763677, 0.156843003413303, 0.002748082456053, 0.00202677073171519, - 0.00382360695862248, -0.000122364309010211, 5.33354637965168e-05, 3.93641210098335e-05, - 4.06398431916703e-05}, - {3.41223117010734, 1.1597568029329, 0.31881674291653, -0.000382400010917784, - -0.000754945672515052, -0.00079200882313927, 0.000145713118224563, -0.00026910957285589, - 0.000137876961532787, -0.000326798596746712}, - {6.23333031852853, 1.24902998148103, -0.0162317540018123, -0.00338184464699201, - 0.000420329743164687, 0.00202038442335185, -7.10435889754986e-05, -6.04039458988991e-06, - 7.25318569569788e-06, -2.5930447720704e-05}, - {191.759784636909, -10.5228276216193, 8.48306234734519, 0.243240262512846, -0.344226468125615, - 0.126267158197535, -0.00186612281541009, 0.00304415728817747, -0.00304958575196089, - 0.000457236034569107}, - {5.61375025356727, 1.1692295110657, 0.224665256727786, -0.00230481633344849, - -0.00746693012026367, -0.00172583925345173, -7.00823444553058e-06, 7.31362778266959e-05, - 5.81988007269583e-05, 1.3723604109425e-05}, - {98.0250669452855, -2.18500123986039, -6.68238707939385, 0.000754807832106659, - 0.256133336978808, 0.110826583415768, 0.000457663127670018, -0.00197655629847616, - -0.00254305206375073, -0.000466731538082995}}; - float sus2coeffBeta[9][10] = { - {41.1102358678699, 2.3034699186519, 2.74551448799899, 0.061701310929235, 0.0317074142089495, - 0.0308171492962288, 0.00049453042200054, 0.000519222896270701, 2.85420168881716e-05, - 0.000259197384126413}, - {4.46821725251333, 0.0125273331991983, 1.32640678842532, 0.000543566569079156, - 0.00396616601484022, -0.00488408099728387, -3.05734704054868e-06, 7.3424831303621e-05, - -5.49439160235527e-05, -8.30708110469922e-05}, - {64.773396165255, 2.97057686090134, -1.90770757709096, 0.062747116236773, -0.077990648565002, - 0.0613989204238974, 0.00055512113297293, -0.000347045533958329, 0.00104059576098392, - -0.000348638726253297}, - {3.10352939390402, -0.2376108554276, 1.60523925160222, 0.00116454605680723, -0.0067958260462381, - 0.0136561370875238, 2.59929059167486e-05, 3.33825895937897e-05, -5.55828531601728e-05, - 0.000109833374761172}, - {0.156052891975873, -0.320721597024578, 1.15208488414874, 0.00164743688819939, - 0.000534718891498932, 0.000469870758457642, 0.000308432468885207, 0.00011789470679678, - 0.000292373398965513, 0.000183599033441813}, - {2.84967971406268, -0.21374251183113, 1.09938586447269, 2.34894704600407e-05, - 0.00588345375399262, 0.00296966835738407, 8.42707308834155e-06, 2.81870099202641e-06, - -3.56732787246631e-05, -7.04534663356379e-05}, - {-7.59892007483895, 0.358662160515702, 0.805137646978357, 0.00222144376998348, - 0.0464438387809707, 0.00847551828841782, 3.24805702347551e-05, 5.45500807838332e-05, - 0.000941378089367713, 0.000353137737023192}, - {-4.65367165487109, 0.201306010390421, 1.19135575710523, -0.00692801521395975, - 0.00394118754078443, 0.00426360093528599, 6.297683536736e-05, -7.15794236895102e-05, - -7.47076172176468e-05, -1.94516917836346e-05}, - {-59.5882618930651, 3.84530212586425, 3.50497032358686, -0.116100453177197, -0.0380997421813177, - -0.0581898335691109, 0.00111464935006159, 0.000559313074537689, 0.000168067749764069, - 0.000563224178849256}}; - float sus3coeffAlpha[9][10] = { - {-174.687021034355, -7.53454036765748, -9.33798316371397, -0.18212338430986, -0.242523652239734, - -0.202086838965846, -0.00138648793335223, -0.00225430176012882, -0.00198887215340364, - -0.00160678535160774}, - {6.92009692410602, 1.8192037428209, 0.254908171908415, 0.0179273243472017, 0.00894059238779664, - -0.000436952529644, 0.000138070523903458, 9.22759645920339e-05, -9.4312261303588e-06, - -1.76647897892869e-05}, - {-17.9720006944368, 0.230510201259892, 1.10751755772907, -0.00973621304161327, - 0.0554450499198677, -0.00590970792122449, -2.92393772526592e-05, 0.000444329929586969, - -0.000436055839773919, -9.5869891049503e-05}, - {-4.9880829382985, 1.33627775121504, -0.330382157073243, 0.00306744056311184, - 0.00376353074674973, -0.0107453978169225, -0.00010680477021693, 5.17225535432745e-05, - 7.4423443938376e-05, -0.000107927900087035}, - {0.952867982900728, 1.14513280899596, 0.307744203675505, 0.000404669974219378, - -0.000737988606997615, 0.00120218232577844, 0.000191147653645603, -0.000275058867995882, - 0.000137187356620739, -0.000320202731145004}, - {8.076706574364, 1.31338618710295, -0.334634356394277, -0.00209719438033295, - -0.00381753503582303, 0.0100347823323616, -7.00550548221671e-05, -1.97626956996069e-05, - 7.80079707003333e-05, -8.95904360920744e-05}, - {-82.4748312650249, 8.63074484663009, -0.949295700187556, -0.178618807265278, 0.130143669167547, - 0.0284326533865768, 0.00149831261351137, -0.0011583692969717, 0.0010560778729661, - 0.000635404380970666}, - {3.34457857521978, 1.09242517408071, 0.241722402244944, 0.00381629887587041, - -0.00863580122530851, 0.00137050492069702, -8.91046701171713e-05, 8.44169683308007e-05, - -3.54608413548779e-05, 8.54042677832451e-06}, - {78.1540457908649, -1.30266922193303, -5.33605443700115, 0.0184226131926499, 0.146629920899062, - 0.110698519952472, 6.64041537651749e-05, -0.00120174584530713, -0.00133177694921411, - -0.000796422644338886}}; - float sus3coeffBeta[9][10] = { - {-31.5704266802979, -5.10700699133189, 2.84549700473812, -0.122701561048957, -0.11257100034746, - 0.102120576206517, -0.000796645106694696, -0.00192211266325167, -4.99981232866237e-05, - 0.00104036677004523}, - {-0.734294938181273, -0.0694317595592039, 1.34746975389878, -0.00103465544451119, - 0.00389798465946559, -0.00308561832194191, -2.91843250099708e-06, 7.59634622232999e-05, - -6.54571602919161e-05, -0.000104146832644606}, - {24.2649069708536, 3.08145095664586, 1.88975821636026, 0.0767528234206466, -0.0526971951753399, - -0.0477053831942802, 0.000613806533422364, -0.000631628059238499, 0.00026217621127941, - 0.000555307997961608}, - {0.62884078560034, -0.152668817824194, 1.70304497205574, 0.000894387499536142, - -0.00306495168098874, 0.0180087418010658, 1.74990847586174e-05, 3.1263263531046e-05, - -7.1643235604579e-06, 0.000147876621100347}, - {-3.05400297018165, -0.316256447664344, 1.14841722699638, 0.000671621084688467, - -0.000906765726598906, 0.000687041032077189, 0.000323419818039841, 0.000128019308781935, - 0.000286018723737538, 0.000192248693306256}, - {-4.39855066935163, -0.322858945262125, 1.44405016355615, -4.93181749911261e-05, - 0.0127396834052722, -0.00523149676786941, 2.56561922352657e-05, 7.61202764874326e-06, - -0.00014623717850039, 8.12219846932013e-06}, - {110.820397525173, -10.9497307382094, 2.48939759290446, 0.296585618718034, -0.142611297893517, - -0.0141810186612052, -0.00275127095595919, 0.00160686698368569, -0.000872029428758877, - -0.000410522437887563}, - {-7.15740446281205, 0.104233532313688, 1.13155893729292, -0.00350418544400852, - 0.00532058598508803, 0.00459314980222008, 3.09155436939349e-05, -7.60935741692174e-05, - -5.87922606348196e-05, 2.56146268588382e-05}, - {44.8818060495112, -7.94729992210875, 3.59286389225051, 0.217944601088562, 0.108087933176612, - -0.116711715153385, -0.00194260120960441, -0.0015752762498594, -0.000331129410732722, - 0.00125896996438418}}; - float sus4coeffAlpha[9][10] = { - {-12.4581187126738, 0.398038572289047, -0.438887880988151, -0.00965382887938283, - -0.0309322349328842, -0.00359106522420111, -7.79546112299913e-06, -0.000432733997178497, - -9.79031907635314e-05, -1.49299384451257e-05}, - {8.41054378583447, 1.87462327360707, 0.266809999719952, 0.0216455385250676, 0.00879426079919981, - -0.00142295319820553, 0.000194819780653264, 8.57549705064449e-05, -3.56478452552367e-05, - -1.65680920554434e-05}, - {16.4141780945815, 2.57697842088604, 0.373972171754278, 0.0498264199400303, 0.0183175817756131, - -0.008545409848878, 0.000422696533006382, -0.000268245978898508, -0.000663188021815416, - -7.51144017137827e-05}, - {0.796692054977593, 1.26773229735266, 0.247715261673662, 0.00358183885438128, - 0.00216435175662881, 0.00713732829335305, -0.000110129715615857, 3.56051594182427e-05, - 5.03074365340535e-05, 8.40279146176271e-05}, - {2.37491588500165, 1.05997969088519, 0.309540461340971, -0.000405047711742513, - 0.000462224730316111, -0.00201887171945793, 0.000260159805167265, -0.000282867209803598, - 0.000201613303652666, -0.000277796442847579}, - {6.36749007598708, 1.31659760017973, -0.122724934153231, -0.00328808937096891, - -0.00577347207798776, 0.00403172074457999, -7.45676459772001e-05, 1.79838644222274e-05, - 0.000104552066440564, -2.78115121929346e-05}, - {-47.9667098848496, 3.97703197139796, -1.96403894754299, -0.0577989657406978, - 0.0634225576208007, -0.0346023445055141, 0.00045886475369098, -0.000326132951996844, - 0.000716490441845967, -0.000136132038635483}, - {6.21505474256094, 0.871830486201601, 0.286906473833627, 0.007875292606045, - -0.00974634725746389, 0.00128416935792136, -0.000111796743751489, 0.000102016719989187, - -3.3503088289589e-05, -1.03874407813931e-05}, - {102.09801265482, -4.12715152309748, -5.04594403360339, 0.075499959116996, 0.216574192561683, - 0.0750031215784663, -0.000147358932612646, -0.0023710703422108, -0.00143310719642393, - -0.000431914403446768}}; - float sus4coeffBeta[9][10] = { - {-21.5077132684032, -1.60004839699939, -0.0298995033958561, -0.0315563250430659, - -0.0424403625879891, -0.0245426225510417, -0.000209861203016225, -0.000422150973104431, - -0.00030514398458781, -0.000211986731019738}, - {9.07644247897601, 0.207457289788099, 1.26735366597312, 0.00768477352180427, - 0.00429230749575816, -0.00514802326062087, 7.56149591998578e-05, 8.42794730840662e-05, - -3.62215715492783e-05, -5.24384190165239e-05}, - {-33.5225408043693, -3.11167857248829, 1.91760591695775, -0.0963752386435729, - 0.00026620241534153, -0.0256680391021823, -0.00102188712837393, 2.63753563968978e-05, - 0.000113172463974702, 0.000271939918507175}, - {19.1379025029401, -0.225979661987912, 2.72337120022998, -0.00136982412154458, - -0.00447301210555274, 0.046496718064139, 2.09123846958985e-05, -4.30383094864847e-05, - -1.22808643520768e-05, 0.000440555709696048}, - {2.957867714783, -0.316069593806939, 1.06379930645214, 0.00103244713047271, 0.00148059212230411, - 0.000557885068990542, 0.000288633931072557, 0.000172775380291659, 0.000269738457990237, - 0.000254577019084984}, - {2.04155199929521, -0.318303488378033, 1.37820715117028, 0.00114788656817743, - 0.0130051117909245, -0.00743109928493789, 1.22403390396844e-05, -3.19245785131217e-05, - -0.000156735218010879, 3.81458400945988e-05}, - {27.314954181241, -1.43916155634084, 2.48967706992348, 0.0278695408478388, -0.0341141456915131, - 0.0281959785297513, -0.000252996164135396, 0.000163365679366542, -0.000380129463154642, - 0.000159350154429114}, - {-0.274693278266294, 0.0199711721436635, 1.26676843352524, -0.0006713759238817, - -0.00389715205101059, 0.00294298337610857, -9.58643121413979e-06, 6.30700938550725e-05, - -6.07188867796123e-05, 7.72199861279611e-06}, - {-74.1601853968901, 2.55641628908672, 6.38533530714782, -0.0582345132980647, - -0.0653804553172819, -0.138850555683872, 0.000489364157827405, 0.000469559629292745, - 0.000698140692952438, 0.00123017528239406}}; - float sus5coeffAlpha[9][10] = { - {-12.1398741236355, 1.99425442858125, -1.9303044815802, 0.0418421279520049, -0.0309683799946315, - -0.0562201123081437, 0.000522607299552916, -0.000375386573815007, -0.000183899715035788, - -0.000600349486293698}, - {4.51862054729553, 1.72396080253297, 0.274562680698765, 0.0162681383591035, 0.0108410181586673, - -0.000272215427359511, 0.000124164068046579, 0.000125586897851351, -1.24082224214974e-05, - -1.63339067540159e-05}, - {63.0100748193658, 7.78014670478172, 0.327263471268564, 0.181264302704374, -0.0652454854214506, - -0.03906716801285, 0.00166924078925478, -0.000749939315526625, 0.000320696101132374, - 0.000499934751180042}, - {-2.14377722994325, 1.33617641673436, 0.0973465660282871, 0.00389526886867845, - 0.00526064997381395, 0.00244964888333519, -8.59416490903541e-05, 4.58871931007681e-05, - 8.6123353128647e-05, 2.85447259858337e-05}, - {0.164792977301912, 1.17541977248641, 0.348838798760518, -0.000180865118417534, - 0.000331789515553421, -0.000734333865631793, 9.76677859410759e-05, -0.000324347075049525, - 8.66683396011167e-05, -0.000385839566009832}, - {-0.228934187493575, 1.30552820143752, 0.306779576899158, -0.00508763741184706, - -0.00318524263093038, -0.00878095392529144, -6.59040013073836e-05, 8.69122529321691e-05, - 5.73853071731283e-05, 8.56628414466758e-05}, - {22.6047744510684, -0.591739857860868, 0.566728856847393, 0.0498124268150265, - -0.0214126910277926, 0.00538091942017912, -0.000391517685229849, 0.000554321668236216, - 0.000191004410219065, 0.000102775124022018}, - {4.54704081104052, 0.844841244606025, 0.181355971462193, 0.0109743851006749, - -0.00363467884122547, 0.00108873046814694, -0.000153236888951059, 3.14623342713789e-06, - -2.78503202185463e-05, 3.99983788680736e-06}, - {-30.878359404848, 5.20536009886854, -0.674455093700773, -0.10801865891189, -0.0514805639475938, - 0.0503660452068572, 0.00072776817295273, 0.00120288537038655, -0.000301602375634166, - -0.000477098479809266}}; - float sus5coeffBeta[9][10] = { - {16.8155737032787, 0.65475660868259, 1.95532810363711, 0.000295624718662669, 0.0426379914736747, - 0.00192544771588337, -4.94534888281508e-05, 8.32299142575155e-05, 0.000645497238623369, - -0.000234155227840799}, - {9.48268090632318, 0.528942263930744, 1.34030963800712, 0.0173605129814363, 0.00581086655972212, - -0.00365006277801141, 0.000180048140973223, 0.000102002650672644, -4.10833110241736e-05, - -8.7810396165556e-05}, - {-47.8325489165383, -4.78262055949503, 1.66912859871505, -0.143518014673292, 0.0288441527062856, - -0.00322823115861497, -0.00148509910480755, 0.000284265179004289, -0.000175299737313045, - -7.04175618676909e-05}, - {3.70510151312723, -0.272200626024415, 1.5527519845099, 0.000589727630962265, - -0.00889682554869096, 0.0109857452472628, 3.05876215574877e-05, 2.09194236165814e-05, - -8.33769024439277e-05, 6.90991113575066e-05}, - {0.820199776906695, -0.355683467192776, 1.17142130858009, -0.000160174871610729, - 4.09723480153701e-05, 0.000209103751629257, 0.000390331989170637, 6.45642836249667e-05, - 0.000318092703362044, 0.000107158633760141}, - {5.52084497768914, -0.227775345312466, 0.845897282556327, 0.00157426476122436, - 0.00657189797805861, 0.0103797665963117, 2.51479848048895e-05, -4.78371400399983e-05, - -5.20221896473413e-05, -0.000143840492906166}, - {-33.4875689683454, 0.937557276329106, -1.02741065470967, -0.0140023273976314, - 0.0401908729477037, -0.0512457211360142, 7.05537967426573e-05, -0.00027521752411122, - 0.000407657552700476, -0.000458411000693613}, - {0.931346887326171, -0.320804452025793, 1.28866325376154, 0.00912456151698805, - -0.00404367403569981, 0.00477543659981282, -9.43987917474817e-05, 4.66464249533497e-05, - -7.89362487264572e-05, -1.0951496495443e-05}, - {-38.3689359928435, 3.8540516906071, 1.26391725545116, -0.108584643500539, -0.0542697403292778, - 0.0285360568428252, 0.000845084580479371, 0.00114184315411245, -0.000169538153750085, - -0.000336529204350355}}; - float sus6coeffAlpha[9][10] = { - {13.0465222152293, 0.0639132159808454, 2.98083557560227, -0.0773202212713293, - 0.0949075412003712, 0.0503055998355815, -0.00104133434256204, 0.000633099036136146, - 0.00091428505258307, 0.000259857066722932}, - {1.66740227859888, 1.55804368674744, 0.209274741749388, 0.0123798418560859, 0.00724950517167516, - -0.000577445375457582, 8.94374551545955e-05, 6.94513586221567e-05, -1.06065583714065e-05, - -1.43899892666699e-05}, - {8.71610925597519, 1.42112818752419, -0.549859300501301, 0.0374581774684577, 0.0617635595955198, - 0.0447491072679598, 0.00069998577106559, 0.00101018723225412, -4.88501228194031e-06, - -0.000434861113274231}, - {-2.3555601314395, 1.29430213886389, 0.179499593411187, 0.00440896450927253, - 0.00352052300927628, 0.00434187143967281, -9.66615195654703e-05, 3.64923075694275e-05, - 6.09619017310129e-05, 4.23908862836885e-05}, - {-0.858019663974047, 1.10138705956076, 0.278789852526915, -0.000199798507752607, - 0.00112092406838628, -0.00177346866231588, 0.000217816070307086, -0.000240713988238257, - 0.000150795563555828, -0.000279246491927943}, - {7.93661480471297, 1.33902098855997, -0.64010306493848, -0.00307944184518557, - -0.00511421127083497, 0.0204008636376403, -9.50042323904954e-05, 6.01530207062221e-05, - 9.13233708460098e-05, -0.000206717750924323}, - {16.2658124154565, 0.191301571705827, 1.02390350838635, 0.0258487436355216, -0.0219752092833362, - 0.0236916776412211, -0.000350496453661261, -0.000123849795280597, -0.000532190902882765, - 9.36018171121253e-05}, - {-1.53023612303052, 1.29132951637076, 0.181159073530008, -0.0023490608317645, - -0.00370741703297037, -0.000229071300377431, -1.6634455407558e-05, 1.11387154630828e-05, - 1.02609175615251e-05, -9.64717658954667e-06}, - {-32.9918791079688, 0.093536793089853, 4.76858627395571, 0.0595845684553358, -0.054845749101257, - -0.133247382500001, -0.000688999201915199, 7.67286265747961e-05, 0.000868163357631254, - 0.00120099606910313}}; - float sus6coeffBeta[9][10] = { - {12.7380220453847, -0.6087309901836, 2.60957722462363, -0.0415319939920917, 0.0444944768824276, - 0.0223231464060241, -0.000421503508733887, -9.39560038638717e-05, 0.000821479971871302, - -4.5330528329465e-05}, - {1.96846333975847, -0.33921438143463, 1.23957110477613, -0.00948832495296823, - 0.00107211134687287, -0.00410820045700199, -9.33679611473279e-05, 3.72984782145427e-05, - -4.04514487800062e-05, -7.6296149087237e-05}, - {5.7454444934481, -1.58476383793609, -0.418479494289251, -0.0985177320630941, - -0.0862179276808015, 0.0126762052037897, -0.00118207758271301, -0.000190361442918412, - 0.0011723869613426, 0.000122882034141316}, - {2.11042287406433, -0.225942746245056, 1.18084080712528, -0.00103013931607172, - -0.00675606790663387, -0.00106646109062746, 1.7708839355979e-05, -3.13642668374253e-05, - -5.87601932564404e-05, -3.92033314627704e-05}, - {2.96049248725882, -0.286261455028255, 1.09122556181319, -0.000672369023155898, - 0.000574446975796023, 0.000120303729680796, 0.000292285799270644, 0.000170497873487264, - 0.000259925974231328, 0.000222437797823852}, - {1.65218061201483, -0.19535446105784, 1.39609640918411, 0.000961524354787167, - 0.00592400381724333, -0.0078500192096718, -7.02791628080906e-07, -2.07197580883822e-05, - -4.33518182614169e-05, 4.66993119419691e-05}, - {-19.56673237415, 1.06558565338761, 0.151160448373445, -0.0252628659378108, 0.0281230551050938, - -0.0217328869907185, 0.000241309440918385, -0.000116449585258429, 0.000401546410974577, - -0.000147563886502726}, - {1.56167171538684, -0.155299366654736, 1.20084049723279, 0.00457348893890231, - 0.00118888040006052, 0.0029920178735941, -5.583448120596e-05, -2.34496315691865e-05, - -5.3309466243918e-05, 6.20289310356821e-06}, - {1.95050549495182, -2.74909818412705, 3.80268788018641, 0.0629242254381785, 0.0581479035315726, - -0.111361283351269, -0.00047845777495158, -0.00075354297736741, -0.000186887396585446, - 0.00119710704771344}}; - float sus7coeffAlpha[9][10] = { - {-92.1126183408754, -3.77261746189525, -4.50604668349213, -0.0909560776043523, - -0.15646903318971, -0.0766293642415356, -0.00059452135473577, -0.00144790037129283, - -0.00119021101127241, -0.000460110780350978}, - {1.60822506792345, 1.12993931449931, 0.300781032865641, -0.00405149856360946, - 0.0116663280665617, -0.000746071920075153, -8.36092173253351e-05, 0.000126762041147563, - -1.57820750462019e-05, -2.13840141586661e-05}, - {-151.403952985468, -5.77049222793992, 9.71132757422642, -0.113259116970462, 0.284142453949027, - -0.198625061659164, -0.000836450164210354, 0.00174062771509636, -0.00323746390757859, - 0.00124721932086258}, - {3.47391964888809, 1.28788318973591, 0.358380140281919, 0.0033863520864927, 0.00154601909793475, - 0.0103457296050314, -9.56426572270873e-05, 5.48838958555808e-05, 2.97537427220847e-05, - 0.000104735911514185}, - {3.32650947866065, 1.16701012685798, 0.293514063672376, -0.00065850791542434, - -8.61746510464303e-05, -0.00212038990772211, 0.00010377123197, -0.000262818127593837, - 0.000103360882478383, -0.000296739688930329}, - {-0.440176043435378, 1.18923278867097, 0.519516382652818, -0.00138846714677511, - 0.00266491699926247, -0.014254675949624, -4.20279929822439e-05, -5.49260281515447e-05, - -1.00328708454487e-05, 0.000138142092498215}, - {9.54962966738358, 1.83809145920811, 1.82162819067959, -0.0116786627338505, - -0.00496037444422313, 0.0590883547819332, 7.48465315787857e-05, 0.000221693951602584, - 7.96466345174136e-06, 0.000638822537725177}, - {7.04862901290925, 0.876813777672465, 0.16368093989381, 0.00928717461441627, - -0.00276538956293246, 0.00117995419940653, -0.000141511492474493, -6.09796031786385e-06, - -2.62114930414747e-05, -2.88713611443788e-06}, - {135.349147631811, -7.21933296299596, -6.02379024934871, 0.19557354282067, 0.207680233512614, - 0.12880101618361, -0.00169832076532024, -0.00192216719797732, -0.00188763612041332, - -0.00103101801961442}}; - float sus7coeffBeta[9][10] = { - {-12.7115487367622, -1.08890790360556, 0.0579616268854079, -0.0212303293514951, - -0.0395948453851818, -0.0275564242614342, -0.000228652851842222, -0.000148106159109458, - -0.000555136649469199, -0.000198260004582737}, - {-0.988147625946871, -0.759018567468546, 1.20998292002818, -0.0241231836977845, - -0.000572110443300516, -0.00294835038249426, -0.00026533039022186, 6.82250069765274e-06, - 7.21038415209318e-06, -6.54881435118179e-05}, - {98.0979345921564, 4.27381413621355, -4.39956005193548, 0.0709109587666745, -0.172774236139236, - 0.107243391488741, 0.000421832640471043, -0.00140450884710288, 0.00158019019392239, - -0.00078512547169536}, - {4.10892685652543, -0.229301778557857, 1.33380992987117, -0.000250095848720304, - -0.00555205065514645, 0.00355052914398176, 1.62727119770752e-05, -1.26026527654764e-05, - -3.25505031810898e-05, 5.79970895921158e-06}, - {3.09432502337258, -0.300556003790433, 1.17085811008124, 0.00128679594824324, - 0.00148229981422985, 9.15267474159147e-05, 0.000300497843413856, 6.31378865575566e-05, - 0.000258447032558814, 9.79142983264352e-05}, - {8.92336134924575, -0.197306981784312, 0.659908505354084, 0.00175572239373996, - 0.006801023678097, 0.0189775987436792, 9.2187857727721e-06, -4.8706332690626e-05, - -6.887009887486e-05, -0.000266455617735054}, - {-52.0734887320227, 2.64822385560272, -1.72387600304694, -0.0383944891609251, 0.110873671161269, - -0.0475247245070445, 0.000194652401328063, -0.000697307928990137, 0.00124021816001, - -0.000194213899980878}, - {2.08203985879155, -0.127503525368396, 1.17628056094647, 0.00283288065938444, - 0.00394668214608305, 0.00314868636161131, -2.99504350569853e-05, -7.11070816314279e-05, - -6.30148122529749e-05, 2.28114298989664e-05}, - {191.321181158032, -12.2449557187473, -7.21933741885107, 0.267954293388644, 0.331529493933124, - 0.149867703984027, -0.00222279201444128, -0.00284724570619954, -0.00298774060233964, - -0.000988903783752156}}; - float sus8coeffAlpha[9][10] = { - {5.46354311880959, 1.15370126035432, 0.568432485840475, -0.00105094692478431, - -0.000472899673842554, 0.015581320536192, 2.26460844314248e-05, -0.000254397947062058, - 0.000198938007250408, 0.000102026690279006}, - {8.8976133108173, 1.89502416095352, 0.268670471819199, 0.0217013413241972, 0.00973925295182384, - -0.00116357269193765, 0.000185865842232419, 0.000103311614912702, -2.46539447920969e-05, - -2.06292928734686e-05}, - {-45.4550803910752, 1.27220123406993, 5.21483855848504, 0.0315791081623634, 0.0725172355124129, - -0.13947591535243, 0.000412577580637848, 0.000434545096994917, -0.000840043932292312, - 0.00126857487044307}, - {1.81302768546433, 1.20563501267535, 0.344815267182167, 0.00546879453241056, - -0.00115382996865884, 0.010597876132341, -7.75885604486581e-05, 8.99568815949154e-05, - -2.98129544974679e-06, 0.000108913239345604}, - {2.19111439539173, 1.06951675598148, 0.283707798607213, 0.00016478588207518, - 0.000196086067268121, -0.00214980231173703, 0.000237820475654357, -0.000256402967908595, - 0.000165966620658577, -0.000268394081675921}, - {15.0858674915897, 1.27922724811168, -1.0803137812576, -0.00184009775302466, - -0.00458792284209219, 0.0359393555418547, -6.05121024079603e-05, -1.2288384024143e-05, - 8.55484605384438e-05, -0.000379241348638065}, - {-14.9594190080906, 1.79473182195746, -1.00830704063572, 0.000890685410857856, - 0.0408932029176081, -0.0165460857151619, -0.000170544299916973, -0.000370901607010145, - 0.000324089709129097, -9.33010240878062e-05}, - {0.867614491733251, 1.38248194737027, 0.233408537422123, -0.00772942878114575, - -0.00783126068079782, -0.000413713955432221, 4.5775750146291e-05, 6.97323029940275e-05, - 1.70664456940787e-05, 6.75517901233086e-06}, - {2.34474364146174, -0.777275400251477, 2.09531381577911, 0.0170780716714389, 0.102855060371092, - -0.1203441505925, 0.000187004964420911, -0.00141720441050986, -0.000336251285258365, - 0.00145175125888695}}; - float sus8coeffBeta[9][10] = { - {28.3033101237397, 1.77504446792811, 1.70758838986317, 0.0307800697044683, 0.0598759344275936, - -0.014461432284373, 0.000128415617799076, 0.000664419128546701, 0.000312923304130995, - -0.000269026446641855}, - {7.73040563051023, 0.0267291479555493, 1.16189582308493, 0.000611047892976521, - -0.00213680506915073, -0.00517435586596902, -3.60304406049766e-06, -1.74452976404459e-05, - -3.95396925228538e-05, -7.01948519410633e-05}, - {-48.0766126130725, -3.77981206700298, 3.03482861087335, -0.0678496412519532, 0.115260678424016, - -0.0109681510065038, -0.000438011443691466, 0.00097230136258486, -0.000930875177732769, - -0.000203144239955507}, - {12.1881935626341, -0.234345089308583, 2.01134619426134, 0.000181529284001169, - -0.00642848065105061, 0.0243985799415726, 2.0224042581776e-05, 5.22503286757285e-06, - -4.75196303016323e-05, 0.000221160482364556}, - {3.49559433498742, -0.294995112674766, 1.07892379698257, 0.000861664794052587, - 0.00138978933062055, 0.000436385106465176, 0.000288095124755908, 0.000147259769247883, - 0.000256686898599516, 0.000198982412957039}, - {9.36663996178607, -0.171266136751803, 0.799869891484541, -0.000896305696610864, - 0.00477919972789653, 0.0077876110326094, 9.16475263625076e-06, 3.02461250100473e-05, - -3.63917701783264e-05, -0.000101376940843402}, - {9.93372683055145, 1.02056557854246, 3.01635426591734, -0.0477113881140277, -0.0280426434406976, - 0.0438813017696874, 0.000470431190169998, -7.55753674679743e-05, -0.000516444906323815, - 0.000253844418223843}, - {4.12868774589741, -0.305711790187688, 1.15739216407191, 0.00942395115281056, - 0.00264758462357433, 0.00227985850688479, -0.000107537164019682, -4.91396736189963e-05, - -5.3803493814502e-05, 6.80587059728718e-06}, - {64.9193383444005, -1.57724255547465, -3.82166532626293, 0.0104712238987591, 0.0898786950946473, - 0.128910456296131, -8.27123227422217e-05, -0.000143979624107479, -0.00146684876653306, - -0.00102226799570239}}; - float sus9coeffAlpha[9][10] = { - {65.8975109449121, 2.19115342242175, 6.11069527811832, -0.0219884864133703, 0.119985456538482, - 0.142746712551924, -0.000465882328687976, 0.000606525132125852, 0.00141667074621881, - 0.00109715845894006}, - {5.70337356029945, 1.86705636976809, 0.235584190291708, 0.0194937327615426, 0.00973291465247784, - -0.00155675297510773, 0.000147099297988423, 0.000115708967219349, -4.1462310493722e-05, - -9.80097031103588e-06}, - {138.221145997284, 6.07665575619595, -9.08085914250542, 0.0839801072927519, -0.143071750033303, - 0.237868300719915, 0.000626693630444932, -0.000579788170871402, 0.00181740650944343, - -0.00207086879728281}, - {-7.78295582666151, 1.37506685179192, -0.507596181420042, 0.00350118305456038, - 0.00380814310115541, -0.0174012437563343, -0.000124801268056815, 2.96314830184492e-05, - 6.3416992450033e-05, -0.000190177262510221}, - {0.13102597129751, 1.24228303845143, 0.328808873447393, 2.6858679536165e-05, - 0.000231428138164498, -0.000584089095259736, 5.5322167970451e-05, -0.000322205709821716, - 7.71348293209208e-05, -0.000393885990364776}, - {4.64571633968935, 1.2668223691397, -0.158952088650432, -0.0038344859267428, 0.0030051503726095, - 0.00455578826025588, -9.42520993914957e-05, 5.81633314412289e-05, -4.43545804544095e-05, - -4.83524454851519e-05}, - {99.2385930314563, -3.65569343617926, 5.54203926675588, 0.0975630395981933, -0.15701634159692, - 0.107834711298836, -0.000885326636237814, 0.000960753844480462, -0.00179894024848343, - 0.000583066757644971}, - {2.82671549736619, 1.11214198870501, 0.214735318432744, 0.00284415167563662, - -0.00743289575690122, 0.000382705440762292, -7.43232442872501e-05, 6.96994098083348e-05, - -4.15108111710131e-06, 1.33520085213482e-05}, - {36.9013743125415, -0.522392401546163, -1.52452843963663, 0.0261375433218879, 0.060573568610239, - 0.0182582125221054, -0.000244373383911157, -0.000271385147292484, -0.000723799969427732, - 6.76324880239196e-05}}; - float sus9coeffBeta[9][10] = { - {128.70886435409, 7.27355509732751, 7.18142203531244, 0.1536100459329, 0.199455846541636, - 0.101824964939793, 0.00116666116789421, 0.00181595584079788, 0.00159271319494017, - 0.000556768406475719}, - {-7.07933839681024, -0.979062424441878, 1.21792546815617, -0.0295740143783226, - -0.00442780611714201, -0.00329612819203176, -0.000291373125216143, -7.47259350176359e-05, - -4.87265282482212e-05, -7.87490350444332e-05}, - {41.1357193180502, 2.75138456414254, -0.0160889117718198, 0.0274001112562423, - -0.145644717742057, -0.0316076203283094, -0.000136443337244472, -0.00153945199081365, - 0.000938960439977633, 0.000599987111822885}, - {2.7980384746608, -0.234741037383589, 1.5342193016705, -0.000993791566721689, - -0.00787533639513478, 0.00927468655141365, 2.63308697896639e-05, -3.42816267184975e-05, - -8.48879419798771e-05, 3.84043821333798e-05}, - {0.427687530667804, -0.346076633694936, 1.22968527483851, -4.95098138311122e-05, - 0.000298245372198029, 0.000332756250024796, 0.00040375986210644, 5.20675972504572e-05, - 0.000327042170278218, 5.93011568264671e-05}, - {4.50337810133314, -0.279364254817202, 0.945812187846199, 0.000116182663432306, - 0.0115646046622083, 0.00908289960302886, 1.90394667311541e-05, -4.4360223646434e-06, - -0.000131398914898614, -0.000145568992865512}, - {-36.3377213654193, 2.21047221783626, 0.0609982245149821, -0.0670546774988572, - 0.016827777144747, -0.0277834084058314, 0.000778301409125556, 0.000135846745194401, - 0.00043261858797068, -0.00021172728254561}, - {-0.737678205841529, -0.217352122193475, 1.23494846329297, 0.00748173441779792, - 0.0019595873704705, 0.00567253723266176, -8.34768773292938e-05, -3.50608394184873e-05, - -0.000107500091550635, -5.1379722947632e-07}, - {-36.6150844777671, 3.24952006904945, 1.7222457840185, -0.0846362445435584, -0.0625549615377418, - 0.019178365782485, 0.000664877496455304, 0.000942971403881222, 0.000190754698755098, - -0.000372226659190439}}; - float sus10coeffAlpha[9][10] = { - {14.4562393748324, 0.669162330324919, 2.13895255446541, -0.0161997097021299, - 0.00185995785065838, 0.0621351118528379, -0.000278999272493087, 0.000238469666491965, - -0.000279407497782961, 0.000726904943739837}, - {-4.45678285887022, 0.92869611919737, 0.186752102727282, -0.00706160758952316, - 0.00532680276723634, -0.00119102617674229, -0.000105283880098953, 3.90673052334419e-05, - -3.13338277344246e-05, 5.32977236959767e-06}, - {30.4255268053197, 3.00991076401191, -1.4855621363519, 0.033934286288413, -0.0553588742704929, - 0.0299275582316466, 0.000167915322354466, -0.00050925078118232, 0.000463662961330962, - -0.000232919143454163}, - {2.45076465343337, 1.30206564388838, 0.635121046212765, 0.00517109639797675, - 0.00360579544364496, 0.0198490668911362, -9.31556816982662e-05, 6.7313653707875e-05, - 6.4669137025142e-05, 0.000209727581169138}, - {-0.784841314851562, 1.10058314980836, 0.314063830836532, 0.000583003703415889, - 0.000312635453606579, -0.000183738114552387, 0.000214096205760617, -0.000286744686021244, - 0.000159157597180407, -0.00032235099420715}, - {7.19568036510586, 1.33307479701657, -0.465585141952456, -0.0031910726544199, - -0.00546273504371797, 0.0145494754402526, -7.9863949693769e-05, 4.83681329120104e-05, - 8.85844309936609e-05, -0.000143217870916994}, - {-12.8344546267449, 1.36023633150143, -0.728527724854506, 0.019982118403416, 0.0385056413989437, - -0.00468598272326268, -0.000303957957649245, -6.37783846968216e-05, 0.000514049116643205, - 0.000112015427600697}, - {-2.58279031298065, 1.42167821629586, 0.208769467511292, -0.00640190372145885, - -0.0056405289717473, 0.000509611313918708, 2.23310562107823e-05, 3.23685469522147e-05, - -7.55982776243849e-06, 2.78417756661088e-06}, - {-29.7178996143914, 2.636972251183, 1.97316329325243, -0.03983524158327, -0.0193152048730234, - -0.0600902798379509, 0.00031786916010672, 0.000162178988605602, 0.000224550786416246, - 0.000614337977361927}}; - float sus10coeffBeta[9][10] = { - {12.4771349792459, 1.44317849705414, 0.975637226331561, 0.0430284146301043, 0.0220810531548995, - -0.0220926906772, 0.000310052324529521, 0.000658151808869523, -0.000288026365111098, - -0.000214619731807045}, - {-0.113203260140131, -0.272424061092191, 1.27704377191184, -0.00791746619331075, - 0.00278646694862191, -0.00398881099259934, -8.09569694307212e-05, 5.99617384829016e-05, - -5.4550919751855e-05, -8.6314530565085e-05}, - {-48.585664295448, -2.04899787231903, 4.48757129623549, -0.0226180460431321, 0.090326735447661, - -0.0722998813632622, -6.77623771415477e-05, 0.000562585419036509, -0.000956171370931993, - 0.000491554402311223}, - {-1.20986884955482, -0.215604107185474, 1.22123198786617, 0.000256508527822089, - -0.00625056735692847, 0.00262961582224303, 2.27433984698861e-05, 1.60471509861372e-05, - -4.85061736834262e-05, -1.8387092782907e-06}, - {-0.250205907903409, -0.315819331560782, 1.09018364376391, -0.000521787614293089, - -0.000500747760913489, 2.48184307342838e-05, 0.000313799238640988, 0.000136669146368744, - 0.000278914324565192, 0.000218512838469476}, - {-1.38512578184076, -0.240456589364121, 1.34170304231345, 0.00017499230372669, - 0.0070862275911073, -0.00460640844814105, 1.27594111036696e-05, -4.73855624902052e-06, - -5.41141037812903e-05, 8.50767021818388e-06}, - {58.9917559342216, -2.28705697628345, 5.35995190407842, 0.0214721399750612, -0.112195722921667, - 0.0890150265857542, -0.000100675657768708, 0.000493488022135339, -0.00137672908303878, - 0.000518683157694955}, - {3.18905073365834, -0.633376549706314, 1.17190259811174, 0.0188817945597344, - 0.00107470708915782, 0.00400880471375267, -0.000197312295539118, -2.46543035998379e-05, - -6.07871064300252e-05, 1.91822310311955e-05}, - {-21.6881499304099, -0.563186103920008, 3.70747028664292, 0.021112883967427, - -0.00650020689049325, -0.0778533644688476, -0.000131921888670268, -0.000402754836445439, - 0.000551249824375055, 0.00062236627391337}}; - float sus11coeffAlpha[9][10] = { - {-5.23569698615548, -1.45500092391928, 2.7643243644756, -0.0762912296128707, - -0.0201645929971608, 0.0997226845779083, -0.000741669441569556, -0.000485368004931528, - 0.000166230212359982, 0.00103455037278067}, - {-7.7405077383712, 0.892040861541276, 0.39014957203484, -0.00952030929935314, - 0.0185577462685363, 0.000500600568760257, -0.000151227821554572, 0.000245334737283439, - 1.89380065823205e-05, 1.83481122973969e-07}, - {-27.462143709831, -1.68192474287299, 0.689411302961069, -0.0146021086710062, 0.227153492753605, - 0.0815806579791421, 2.92919049429149e-05, 0.00153760357651792, -0.00247865821192621, - -0.00166333309739387}, - {-6.74664748624368, 1.43279156053015, 0.0212787292914553, 0.00764792230365732, - 0.00796410301290615, 0.0014384998868733, -8.95239151813685e-05, 9.55245417090909e-05, - 0.000127251739461239, 3.26943341606363e-05}, - {-2.20391533717674, 1.32902400478083, 0.38633027011889, 0.00104660852197061, - 0.00105228824412283, -0.00242067551428214, -6.98346290136652e-05, -0.000369075232184835, - -1.59510520000704e-05, -0.000448565104826966}, - {-5.29476778147188, 1.4549556336236, 0.561334186252557, -0.00260896342687109, - -0.00855934179001141, -0.0182515354646452, -8.79385828606048e-05, 5.98357681659175e-05, - 0.000146570207542509, 0.000201596912834554}, - {-45.7906613832612, 3.77630104475902, -1.67494598155515, -0.0545433897761635, 0.047897938410221, - -0.0355687158405231, 0.000374738707508583, -0.000448453494537518, 0.000377784972619365, - -0.000276573228333836}, - {-9.11681182090372, 2.06933872940742, 0.26131496122122, -0.0259534033367855, - -0.00777266937872862, -0.00262135395843891, 0.000223790782655445, 6.40488537928934e-05, - 7.75581514100296e-05, -9.25934285039627e-06}, - {183.243883340634, -8.02281039502717, -10.0756951652703, 0.168750521462303, 0.314006821405967, - 0.200264755034566, -0.0011895153717447, -0.00253812476819896, -0.00291324393641628, - -0.00140062522117514}}; - float sus11coeffBeta[9][10] = { - {34.4499366074013, -0.438583698052091, 4.72111001451028, -0.041810050989433, 0.0562461093661426, - 0.0856849892524893, -0.000477813051406167, -3.16404257494464e-05, 0.00102633196865105, - 0.000552974013759876}, - {7.6366298088699, 0.150314752958302, 1.31364679484924, 0.00557696667395871, 0.00163731860604376, - -0.00454759608980269, 5.83979683674572e-05, 4.45944881220665e-05, -4.27874746147066e-05, - -8.77418673597557e-05}, - {130.156215011893, 1.85759000444524, -10.986892391833, -0.00686275191260681, -0.188837138116058, - 0.346177462085361, -0.000183276946352264, -0.000702183496893294, 0.00293145272693857, - -0.00318194442670715}, - {-1.67854820161036, -0.358899332859806, 0.956690839640595, -4.93862910503803e-05, - -0.0136134783014874, -0.00848731301504507, 3.75950499927045e-05, 1.35374694383289e-06, - -0.000156596507890443, -0.000123254220377897}, - {3.67569209537767, -0.387260959713287, 1.31343215605952, -0.00206444615206506, - 0.00145334813110285, -0.00151259497696238, 0.000449492568365603, 6.95883968949488e-07, - 0.000368585523744765, -6.3420715525635e-05}, - {14.3296323024886, -0.182979476956897, 0.306817119309235, -0.00022212115978293, - 0.00463485302909649, 0.0277574953550035, 1.1422454625565e-05, 1.06053257479502e-05, - -2.05720000720608e-05, -0.000338584671430337}, - {-18.7534921817754, 1.14272710923224, 0.460498062012866, -0.00995826989278202, - 0.0658502318647112, 0.00616942819937029, -7.70857153768402e-05, -0.000641755741925561, - 0.00047849204592989, 0.000158509018296766}, - {1.26543621388607, -0.176674379740481, 1.38814920935488, 0.00545485262295305, - -0.00499775616702264, 0.0038057039142173, -6.59604252054511e-05, 6.40211116049053e-05, - -6.74778593434431e-05, -2.81973589469059e-05}, - {116.975421945286, -5.53022680362263, -5.61081660666997, 0.109754904982136, 0.167666815691513, - 0.163137400730063, -0.000609874123906977, -0.00205336098697513, -0.000889232196185857, - -0.00168429567131815}}; + float filterAlpha; + float sunThresh; + } susHandlingParameters; - float filterAlpha; - float sunThresh; - } susHandlingParameters; + struct GyrHandlingParameters { + double gyr0orientationMatrix[3][3] = {{0, 0, -1}, {0, -1, 0}, {-1, 0, 0}}; + double gyr1orientationMatrix[3][3] = {{0, 0, -1}, {0, 1, 0}, {1, 0, 0}}; + double gyr2orientationMatrix[3][3] = {{0, 0, -1}, {0, -1, 0}, {-1, 0, 0}}; + double gyr3orientationMatrix[3][3] = {{0, 0, -1}, {0, 1, 0}, {1, 0, 0}}; + } gyrHandlingParameters; - struct RmuHandlingParameters { - double rmu0orientationMatrix[3][3]; - double rmu1orientationMatrix[3][3]; - double rmu2orientationMatrix[3][3]; - } rmuHandlingParameters; + struct RwHandlingParameters { + double rw0orientationMatrix[3][3]; + double rw1orientationMatrix[3][3]; + double rw2orientationMatrix[3][3]; + double rw3orientationMatrix[3][3]; + double inertiaWheel = 0.000028198; + double maxTrq = 0.0032; // 3.2 [mNm] + } rwHandlingParameters; - struct RwHandlingParameters { - double rw0orientationMatrix[3][3]; - double rw1orientationMatrix[3][3]; - double rw2orientationMatrix[3][3]; - double rw3orientationMatrix[3][3]; - double inertiaWheel = 0.000028198; - double maxTrq = 0.0032; //3.2 [mNm] - } rwHandlingParameters; + struct RwMatrices { + double alignmentMatrix[3][4] = {{0.9205, 0.0000, -0.9205, 0.0000}, + {0.0000, -0.9205, 0.0000, 0.9205}, + {0.3907, 0.3907, 0.3907, 0.3907}}; + double pseudoInverse[4][3] = {{0.4434, -0.2845, 0.3597}, + {0.2136, -0.3317, 1.0123}, + {-0.8672, -0.1406, 0.1778}, + {0.6426, 0.4794, 1.3603}}; + double without0[4][3]; + double without1[4][3]; + double without2[4][3]; + double without3[4][3]; + double nullspace[4] = {-0.7358, 0.5469, -0.3637, -0.1649}; + } rwMatrices; - struct RwMatrices { - double alignmentMatrix[3][4] = { - { 0.9205, 0.0000, -0.9205, 0.0000}, - { 0.0000, -0.9205, 0.0000, 0.9205}, - { 0.3907, 0.3907, 0.3907, 0.3907}}; - double pseudoInverse[4][3] = { - { 0.4434, -0.2845, 0.3597}, - { 0.2136, -0.3317, 1.0123}, - { -0.8672, -0.1406, 0.1778}, - { 0.6426, 0.4794, 1.3603}}; - double without0[4][3]; - double without1[4][3]; - double without2[4][3]; - double without3[4][3]; - double nullspace[4] = { -0.7358, 0.5469, -0.3637, -0.1649}; - } rwMatrices; + struct SafeModeControllerParameters { + double k_rate_mekf = 0.00059437; + double k_align_mekf = 0.000056875; - struct SafeModeControllerParameters { - double k_rate_mekf = 0.00059437; - double k_align_mekf = 0.000056875; + double k_rate_no_mekf; + double k_align_no_mekf; + double sunMagAngleMin; - double k_rate_no_mekf; - double k_align_no_mekf; - double sunMagAngleMin; + double sunTargetDir[3] = {1, 0, 0}; // Body frame + double satRateRef[3]; // Body frame - double sunTargetDir[3] = { 1, 0, 0}; //Body frame - double satRateRef[3]; //Body frame + } safeModeControllerParameters; - } safeModeControllerParameters; + struct DetumbleCtrlParameters { + double gainD = pow(10.0, -3.3); - struct DetumbleCtrlParameters { + } detumbleCtrlParameters; - double gainD = pow(10.0,-3.3); + // ToDo: mutiple structs for different pointing mode controllers? + struct PointingModeControllerParameters { + double updtFlag; + double A_rw[3][12]; - } detumbleCtrlParameters; + double refDirection[3] = {1, 0, 0}; + double refRotRate[3] = {0, 0, 0}; + double quatRef[4] = {0, 0, 0, 1}; + bool avoidBlindStr = true; + double blindAvoidStart = 1.5; + double blindAvoidStop = 2.5; + double blindRotRate = 1 * M_PI / 180; - // ToDo: mutiple structs for different pointing mode controllers? - struct PointingModeControllerParameters { - double updtFlag; - double A_rw[3][12]; + double zeta = 0.3; + double zetaLow; + double om = 0.3; + double omLow; + double omMax = 1 * M_PI / 180; + double qiMin = 0.1; + double gainNullspace = 0.01; - double refDirection[3] = { 1, 0, 0}; - double refRotRate[3] = { 0, 0, 0}; - double quatRef[4] = { 0, 0, 0, 1}; - bool avoidBlindStr = true; - double blindAvoidStart = 1.5; - double blindAvoidStop = 2.5; - double blindRotRate = 1 * M_PI /180; + double desatMomentumRef[3] = {0, 0, 0}; + double deSatGainFactor = 1000; + bool desatOn = true; - double zeta = 0.3; - double zetaLow; - double om = 0.3; - double omLow; - double omMax = 1 * M_PI / 180; - double qiMin = 0.1; - double gainNullspace = 0.01; + double omegaEarth = 0.000072921158553; - double desatMomentumRef[3] = {0,0,0}; - double deSatGainFactor = 1000; - bool desatOn = true; + } inertialModeControllerParameters, nadirModeControllerParameters, targetModeControllerParameters; - double omegaEarth = 0.000072921158553; + struct StrParameters { + double exclusionAngle = 20 * M_PI / 180; + // double strOrientationMatrix[3][3]; + double boresightAxis[3] = {0.7593, 0.0000, -0.6508}; // in body/geometry frame + } strParameters; + struct GpsParameters { + } gpsParameters; - } inertialModeControllerParameters, nadirModeControllerParameters, - targetModeControllerParameters; + struct GroundStationParameters { + double latitudeGs = 48.7495 * M_PI / 180.; // [rad] Latitude + double longitudeGs = 9.10384 * M_PI / 180.; // [rad] Longitude + double altitudeGs = 500; // [m] Altitude + double earthRadiusEquat = 6378137; // [m] + double earthRadiusPolar = 6356752.314; // [m] + } groundStationParameters; // Stuttgart + struct SunModelParameters { + enum UseSunModel { NO = 0, YES = 3 }; + uint8_t useSunModel; + float domega = 36000.771; + float omega_0 = 282.94 * M_PI / 180.; // RAAN plus argument of perigee + float m_0 = 357.5256; // coefficients for mean anomaly + float dm = 35999.049; // coefficients for mean anomaly + float e = 23.4392911 * M_PI / 180.; // angle of earth's rotation axis + float e1 = 0.74508 * M_PI / 180.; - struct StrParameters { - double exclusionAngle = 20 * M_PI /180; -// double strOrientationMatrix[3][3]; - double boresightAxis[3] = { 0.7593, 0.0000,-0.6508}; //in body/geometry frame - } strParameters; + float p1 = 6892. / 3600. * M_PI / 180.; // some parameter + float p2 = 72. / 3600. * M_PI / 180.; // some parameter + } sunModelParameters; - struct GpsParameters { - } gpsParameters; + struct KalmanFilterParameters { + uint8_t activateKalmanFilter; + uint8_t requestResetFlag; + double maxToleratedTimeBetweenKalmanFilterExecutionSteps; + double processNoiseOmega[3]; + double processNoiseQuaternion[4]; - struct GroundStationParameters { - double latitudeGs = 48.7495 * M_PI / 180.; // [rad] Latitude - double longitudeGs = 9.10384 * M_PI / 180.; // [rad] Longitude - double altitudeGs = 500; // [m] Altitude - double earthRadiusEquat = 6378137; // [m] - double earthRadiusPolar = 6356752.314; // [m] - } groundStationParameters; // Stuttgart + double sensorNoiseSTR = 0.1 * M_PI / 180; + double sensorNoiseSS = 8 * M_PI / 180; + double sensorNoiseMAG = 4 * M_PI / 180; + double sensorNoiseRMU[3]; - struct SunModelParameters { - enum UseSunModel { - NO = 0, YES = 3 - }; - uint8_t useSunModel; - float domega = 36000.771; - float omega_0 = 282.94 * M_PI / 180.; //RAAN plus argument of perigee - float m_0 = 357.5256; //coefficients for mean anomaly - float dm = 35999.049; //coefficients for mean anomaly - float e = 23.4392911 * M_PI / 180.; //angle of earth's rotation axis - float e1 = 0.74508 * M_PI / 180.; + double sensorNoiseArwRmu; // Angular Random Walk + double sensorNoiseBsRMU; // Bias Stability + } kalmanFilterParameters; - float p1 = 6892. / 3600. * M_PI / 180.; //some parameter - float p2 = 72. / 3600. * M_PI / 180.; //some parameter - } sunModelParameters; + struct MagnetorquesParameter { + 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] - struct KalmanFilterParameters { - uint8_t activateKalmanFilter; - uint8_t requestResetFlag; - double maxToleratedTimeBetweenKalmanFilterExecutionSteps; - double processNoiseOmega[3]; - double processNoiseQuaternion[4]; + } magnetorquesParameter; - double sensorNoiseSTR = 0.1 * M_PI / 180; - double sensorNoiseSS = 8 * M_PI / 180; - double sensorNoiseMAG = 4 * M_PI / 180; - double sensorNoiseRMU[3]; - - double sensorNoiseArwRmu; //Angular Random Walk - double sensorNoiseBsRMU; // Bias Stability - } kalmanFilterParameters; - - struct MagnetorquesParameter { - - 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] - - } magnetorquesParameter; - - struct DetumbleParameter { - - uint8_t detumblecounter; - double omegaDetumbleStart; - double omegaDetumbleEnd; - } detumbleParameter; + struct DetumbleParameter { + uint8_t detumblecounter; + double omegaDetumbleStart; + double omegaDetumbleEnd; + } detumbleParameter; }; #endif /* ACSPARAMETERS_H_ */ -- 2.34.1 From 0f06219fd3a190fd35b11174d951ce91e16427b2 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 11 Oct 2022 14:57:58 +0200 Subject: [PATCH 049/101] changed initial Mgm values to arbitrary other than 0 values --- dummies/ImtqDummy.cpp | 2 +- dummies/MgmLIS3MDLDummy.cpp | 3 ++- dummies/MgmRm3100Dummy.cpp | 3 ++- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/dummies/ImtqDummy.cpp b/dummies/ImtqDummy.cpp index 8765e978..331a6201 100644 --- a/dummies/ImtqDummy.cpp +++ b/dummies/ImtqDummy.cpp @@ -41,7 +41,7 @@ ReturnValue_t ImtqDummy::initializeLocalDataPool(localpool::DataPool &localDataP localDataPoolMap.emplace(IMTQ::MCU_TEMPERATURE, new PoolEntry({0})); localDataPoolMap.emplace(IMTQ::MGM_CAL_NT, new PoolEntry({0.0,0.0,0.0})); localDataPoolMap.emplace(IMTQ::ACTUATION_CAL_STATUS, new PoolEntry({0})); - localDataPoolMap.emplace(IMTQ::MTM_RAW, new PoolEntry({0.0,0.0,0.0})); + localDataPoolMap.emplace(IMTQ::MTM_RAW, new PoolEntry({0.12, 0.76, -0.45}, true)); localDataPoolMap.emplace(IMTQ::ACTUATION_RAW_STATUS, new PoolEntry({0})); return returnvalue::OK; } diff --git a/dummies/MgmLIS3MDLDummy.cpp b/dummies/MgmLIS3MDLDummy.cpp index b89d74b8..31228260 100644 --- a/dummies/MgmLIS3MDLDummy.cpp +++ b/dummies/MgmLIS3MDLDummy.cpp @@ -41,6 +41,7 @@ uint32_t MgmLIS3MDLDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { ReturnValue_t MgmLIS3MDLDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { localDataPoolMap.emplace(MGMLIS3MDL::TEMPERATURE_CELCIUS, new PoolEntry({0.0})); - localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTHS, new PoolEntry({0.0, 0.0, 0.0})); + localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTHS, + new PoolEntry({1.02, 0.56, -0.78}, true)); return returnvalue::OK; } diff --git a/dummies/MgmRm3100Dummy.cpp b/dummies/MgmRm3100Dummy.cpp index cb27209c..1bd4f513 100644 --- a/dummies/MgmRm3100Dummy.cpp +++ b/dummies/MgmRm3100Dummy.cpp @@ -36,6 +36,7 @@ uint32_t MgmRm3100Dummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { ReturnValue_t MgmRm3100Dummy::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) { - localDataPoolMap.emplace(RM3100::FIELD_STRENGTHS, new PoolEntry({0.0, 0.0, 0.0})); + localDataPoolMap.emplace(RM3100::FIELD_STRENGTHS, + new PoolEntry({0.87, -0.95, 0.11}, true)); return returnvalue::OK; } -- 2.34.1 From b2a715ef6ad060eee9d5a911e7c3db4dba9186f7 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 11 Oct 2022 15:00:37 +0200 Subject: [PATCH 050/101] added GYR dummies to acsTask. Added complete GYR dataSets to the dummies --- bsp_q7s/core/InitMission.cpp | 4 ++++ dummies/GyroAdisDummy.cpp | 7 +++++++ dummies/GyroL3GD20Dummy.cpp | 7 ++++--- 3 files changed, 15 insertions(+), 3 deletions(-) diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index 5bac228b..b502c5a4 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -157,6 +157,10 @@ void initmission::initTasks() { acsTask->addComponent(objects::SUS_10_N_LOC_XMYBZF_PT_ZF); acsTask->addComponent(objects::SUS_5_N_LOC_XFYMZB_PT_ZB); acsTask->addComponent(objects::SUS_11_R_LOC_XBYMZB_PT_ZB); + acsTask->addComponent(objects::GYRO_0_ADIS_HANDLER); + acsTask->addComponent(objects::GYRO_1_L3G_HANDLER); + acsTask->addComponent(objects::GYRO_2_ADIS_HANDLER); + acsTask->addComponent(objects::GYRO_3_L3G_HANDLER); #endif PeriodicTaskIF* sysTask = factory->createPeriodicTask( diff --git a/dummies/GyroAdisDummy.cpp b/dummies/GyroAdisDummy.cpp index 42af6412..050c838d 100644 --- a/dummies/GyroAdisDummy.cpp +++ b/dummies/GyroAdisDummy.cpp @@ -40,6 +40,13 @@ uint32_t GyroAdisDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { r ReturnValue_t GyroAdisDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(ADIS1650X::ANG_VELOC_X, new PoolEntry({-0.5}, true)); + localDataPoolMap.emplace(ADIS1650X::ANG_VELOC_Y, new PoolEntry({0.2}, true)); + localDataPoolMap.emplace(ADIS1650X::ANG_VELOC_Z, new PoolEntry({-1.2}, true)); + localDataPoolMap.emplace(ADIS1650X::ACCELERATION_X, new PoolEntry({0.0})); + localDataPoolMap.emplace(ADIS1650X::ACCELERATION_Y, new PoolEntry({0.0})); + localDataPoolMap.emplace(ADIS1650X::ACCELERATION_Z, new PoolEntry({0.0})); localDataPoolMap.emplace(ADIS1650X::TEMPERATURE, new PoolEntry({0.0})); + return returnvalue::OK; } diff --git a/dummies/GyroL3GD20Dummy.cpp b/dummies/GyroL3GD20Dummy.cpp index 935e32f5..a800cd62 100644 --- a/dummies/GyroL3GD20Dummy.cpp +++ b/dummies/GyroL3GD20Dummy.cpp @@ -38,11 +38,12 @@ void GyroL3GD20Dummy::fillCommandAndReplyMap() {} uint32_t GyroL3GD20Dummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + ReturnValue_t GyroL3GD20Dummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { - localDataPoolMap.emplace(L3GD20H::ANG_VELOC_X, new PoolEntry({0.0})); - localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Y, new PoolEntry({0.0})); - localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Z, new PoolEntry({0.0})); + localDataPoolMap.emplace(L3GD20H::ANG_VELOC_X, new PoolEntry({1.2}, true)); + localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Y, new PoolEntry({-0.1}, true)); + localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Z, new PoolEntry({0.7}, true)); localDataPoolMap.emplace(L3GD20H::TEMPERATURE, new PoolEntry({0.0})); return returnvalue::OK; } -- 2.34.1 From 46dd2b92e50da6ab7524617f6f4805704d444c94 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 11 Oct 2022 15:01:32 +0200 Subject: [PATCH 051/101] renamed RMU related stuff to GYR. added GYR processing --- mission/controller/acs/SensorProcessing.cpp | 96 +++++++++++++-------- mission/controller/acs/SensorProcessing.h | 14 ++- mission/controller/acs/SensorValues.cpp | 31 ++++--- mission/controller/acs/SensorValues.h | 20 ++--- 4 files changed, 100 insertions(+), 61 deletions(-) diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index 749ec373..3c6a3564 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -353,62 +353,79 @@ void SensorProcessing::processSus( *sunVectorInertialValid = true; } -void SensorProcessing::processRmu(const double rmu0Value[], bool rmu0valid, - const double rmu1Value[], bool rmu1valid, - const double rmu2Value[], bool rmu2valid, - timeval timeOfrmuMeasurement, - const AcsParameters::RmuHandlingParameters *rmuParameters, - double *satRatEst, bool *satRateEstValid) { - if (!rmu0valid && !rmu1valid && !rmu2valid) { +void SensorProcessing::processGyr( + const double gyr0axXvalue, bool gyr0axXvalid, const double gyr0axYvalue, bool gyr0axYvalid, + const double gyr0axZvalue, bool gyr0axZvalid, const double gyr1axXvalue, bool gyr1axXvalid, + const double gyr1axYvalue, bool gyr1axYvalid, const double gyr1axZvalue, bool gyr1axZvalid, + const double gyr2axXvalue, bool gyr2axXvalid, const double gyr2axYvalue, bool gyr2axYvalid, + const double gyr2axZvalue, bool gyr2axZvalid, const double gyr3axXvalue, bool gyr3axXvalid, + const double gyr3axYvalue, bool gyr3axYvalid, const double gyr3axZvalue, bool gyr3axZvalid, + timeval timeOfGyrMeasurement, const AcsParameters::GyrHandlingParameters *gyrParameters, + double *satRatEst, bool *satRateEstValid) { + if (!gyr0axXvalid && !gyr0axYvalid && !gyr0axZvalid && !gyr1axXvalid && !gyr1axYvalid && + !gyr1axZvalid && !gyr2axXvalid && !gyr2axYvalid && !gyr2axZvalid && !gyr3axXvalid && + !gyr3axYvalid && !gyr3axZvalid) { *satRateEstValid = false; return; } // Transforming Values to the Body Frame (actually it is the geometry frame atm) - double rmu0ValueBody[3] = {0, 0, 0}, rmu1ValueBody[3] = {0, 0, 0}, rmu2ValueBody[3] = {0, 0, 0}; + double gyr0ValueBody[3] = {0, 0, 0}, gyr1ValueBody[3] = {0, 0, 0}, gyr2ValueBody[3] = {0, 0, 0}, + gyr3ValueBody[3] = {0, 0, 0}; - bool validUnit[3] = {false, false, false}; + bool validUnit[4] = {false, false, false, false}; uint8_t validCount = 0; - if (rmu0valid) { - MatrixOperations::multiply(rmuParameters->rmu0orientationMatrix[0], rmu0Value, - rmu0ValueBody, 3, 3, 1); + if (gyr0axXvalid && gyr0axYvalid && gyr0axZvalid) { + const double gyr0Value[3] = {gyr0axXvalue, gyr0axYvalue, gyr0axZvalue}; + MatrixOperations::multiply(gyrParameters->gyr0orientationMatrix[0], gyr0Value, + gyr0ValueBody, 3, 3, 1); validCount += 1; validUnit[0] = true; } - if (rmu1valid) { - MatrixOperations::multiply(rmuParameters->rmu1orientationMatrix[0], rmu1Value, - rmu1ValueBody, 3, 3, 1); + if (gyr1axXvalid && gyr1axYvalid && gyr1axZvalid) { + const double gyr1Value[3] = {gyr1axXvalue, gyr1axYvalue, gyr1axZvalue}; + MatrixOperations::multiply(gyrParameters->gyr1orientationMatrix[0], gyr1Value, + gyr1ValueBody, 3, 3, 1); validCount += 1; validUnit[1] = true; } - if (rmu2valid) { - MatrixOperations::multiply(rmuParameters->rmu2orientationMatrix[0], rmu2Value, - rmu2ValueBody, 3, 3, 1); + if (gyr2axXvalid && gyr2axYvalid && gyr2axZvalid) { + const double gyr2Value[3] = {gyr2axXvalue, gyr2axYvalue, gyr2axZvalue}; + MatrixOperations::multiply(gyrParameters->gyr2orientationMatrix[0], gyr2Value, + gyr2ValueBody, 3, 3, 1); validCount += 1; validUnit[2] = true; } + if (gyr3axXvalid && gyr3axYvalid && gyr3axZvalid) { + const double gyr3Value[3] = {gyr3axXvalue, gyr3axYvalue, gyr3axZvalue}; + MatrixOperations::multiply(gyrParameters->gyr3orientationMatrix[0], gyr3Value, + gyr3ValueBody, 3, 3, 1); + validCount += 1; + validUnit[3] = true; + } /* -------- SatRateEst: Middle Value ------- */ - double rmuValues[3][3] = {{rmu0ValueBody[0], rmu1ValueBody[0], rmu2ValueBody[0]}, - {rmu0ValueBody[1], rmu1ValueBody[1], rmu2ValueBody[1]}, - {rmu0ValueBody[2], rmu1ValueBody[2], rmu2ValueBody[2]}}; - double rmuValidValues[3][validCount]; + double gyrValues[3][4] = { + {gyr0ValueBody[0], gyr1ValueBody[0], gyr2ValueBody[0], gyr3ValueBody[0]}, + {gyr0ValueBody[1], gyr1ValueBody[1], gyr2ValueBody[1], gyr3ValueBody[1]}, + {gyr0ValueBody[2], gyr1ValueBody[2], gyr2ValueBody[2], gyr3ValueBody[2]}}; + double gyrValidValues[3][validCount]; uint8_t j = 0; for (uint8_t i = 0; i < validCount; i++) { if (validUnit[i]) { - rmuValidValues[0][j] = rmuValues[0][i]; - rmuValidValues[1][j] = rmuValues[1][i]; - rmuValidValues[2][j] = rmuValues[2][i]; + gyrValidValues[0][j] = gyrValues[0][i]; + gyrValidValues[1][j] = gyrValues[1][i]; + gyrValidValues[2][j] = gyrValues[2][i]; j += 1; } } // Selection Sort - double rmuValidValuesSort[3][validCount]; - MathOperations::selectionSort(*rmuValidValues, *rmuValidValuesSort, 3, validCount); + double gyrValidValuesSort[3][validCount]; + MathOperations::selectionSort(*gyrValidValues, *gyrValidValuesSort, 3, validCount); uint8_t n = ceil(validCount / 2); - satRatEst[0] = rmuValidValuesSort[0][n]; - satRatEst[1] = rmuValidValuesSort[1][n]; - satRatEst[2] = rmuValidValuesSort[2][n]; + satRatEst[0] = gyrValidValuesSort[0][n]; + satRatEst[1] = gyrValidValuesSort[1][n]; + satRatEst[2] = gyrValidValuesSort[2][n]; *satRateEstValid = true; } @@ -467,8 +484,19 @@ void SensorProcessing::process(acsctrl::SusDataRaw *susData, timeval now, &outputValues->sunVectorDerivativeValid); // VALID outputs ? - // processRmu(sensorValues->rmu0, sensorValues->rmu0Valid, sensorValues->rmu1, - // sensorValues->rmu1Valid, sensorValues->rmu2, sensorValues->rmu2Valid, now, - // &acsParameters->rmuHandlingParameters, outputValues->satRateEst, - // &outputValues->satRateEstValid); + processGyr( + sensorValues->gyr0AdisSet.angVelocX.value, sensorValues->gyr0AdisSet.angVelocX.isValid(), + sensorValues->gyr0AdisSet.angVelocY.value, sensorValues->gyr0AdisSet.angVelocY.isValid(), + sensorValues->gyr0AdisSet.angVelocZ.value, sensorValues->gyr0AdisSet.angVelocZ.isValid(), + sensorValues->gyr1L3gSet.angVelocX.value, sensorValues->gyr1L3gSet.angVelocX.isValid(), + sensorValues->gyr1L3gSet.angVelocY.value, sensorValues->gyr1L3gSet.angVelocY.isValid(), + sensorValues->gyr1L3gSet.angVelocZ.value, sensorValues->gyr1L3gSet.angVelocZ.isValid(), + sensorValues->gyr2AdisSet.angVelocX.value, sensorValues->gyr2AdisSet.angVelocX.isValid(), + sensorValues->gyr2AdisSet.angVelocY.value, sensorValues->gyr2AdisSet.angVelocY.isValid(), + sensorValues->gyr2AdisSet.angVelocZ.value, sensorValues->gyr2AdisSet.angVelocZ.isValid(), + sensorValues->gyr3L3gSet.angVelocX.value, sensorValues->gyr3L3gSet.angVelocX.isValid(), + sensorValues->gyr3L3gSet.angVelocY.value, sensorValues->gyr3L3gSet.angVelocY.isValid(), + sensorValues->gyr3L3gSet.angVelocZ.value, sensorValues->gyr3L3gSet.angVelocZ.isValid(), now, + &acsParameters->gyrHandlingParameters, outputValues->satRateEst, + &outputValues->satRateEstValid); } diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h index df2b2a37..609c6e6a 100644 --- a/mission/controller/acs/SensorProcessing.h +++ b/mission/controller/acs/SensorProcessing.h @@ -52,10 +52,16 @@ class SensorProcessing { bool *sunDirEstValid, double *sunVectorInertial, bool *sunVectorInertialValid, double *sunVectorDerivative, bool *sunVectorDerivativeValid); - void processRmu(const double rmu0Value[], bool rmu0valid, // processRmu - const double rmu1Value[], bool rmu1valid, const double rmu2Value[], - bool rmu2valid, timeval timeOfrmuMeasurement, - const AcsParameters::RmuHandlingParameters *rmuParameters, double *satRatEst, + void processGyr(const double gyr0axXvalue, bool gyr0axXvalid, const double gyr0axYvalue, + bool gyr0axYvalid, const double gyr0axZvalue, bool gyr0axZvalid, + const double gyr1axXvalue, bool gyr1axXvalid, const double gyr1axYvalue, + bool gyr1axYvalid, const double gyr1axZvalue, bool gyr1axZvalid, + const double gyr2axXvalue, bool gyr2axXvalid, const double gyr2axYvalue, + bool gyr2axYvalid, const double gyr2axZvalue, bool gyr2axZvalid, + const double gyr3axXvalue, bool gyr3axXvalid, const double gyr3axYvalue, + bool gyr3axYvalid, const double gyr3axZvalue, bool gyr3axZvalid, + timeval timeOfGyrMeasurement, + const AcsParameters::GyrHandlingParameters *gyrParameters, double *satRatEst, bool *satRateEstValid); void processStr(); diff --git a/mission/controller/acs/SensorValues.cpp b/mission/controller/acs/SensorValues.cpp index 9ca2b90b..3a47937a 100644 --- a/mission/controller/acs/SensorValues.cpp +++ b/mission/controller/acs/SensorValues.cpp @@ -42,20 +42,25 @@ ReturnValue_t SensorValues::updateSus() { return result; } +ReturnValue_t SensorValues::updateGyr() { + ReturnValue_t result; + PoolReadGuard pgGyr0(&gyr0AdisSet), pgGyr1(&gyr1L3gSet), pgGyr2(&gyr2AdisSet), + pgGyr3(&gyr3L3gSet); + + result = (pgGyr0.getReadResult() || pgGyr1.getReadResult() || pgGyr2.getReadResult() || + pgGyr3.getReadResult()); + return result; +} + ReturnValue_t SensorValues::update() { - updateSus(); - updateMgm(); - - // lp_var_t quaternion(objects::STAR_TRACKER, PoolIds::CALI_QW, nullptr, - // pool_rwm_t::VAR_READ); - // ReturnValue_t result = quaternion.read(); - // - // if (result != RETURN_OK) { - // return RETURN_FAILED; - // } - // quatJB[3] = static_cast(quaternion.value); - // quatJBValid = quaternion.isValid(); - + ReturnValue_t mgmUpdate = updateMgm(); + ReturnValue_t susUpdate = updateSus(); + ReturnValue_t gyrUpdate = updateGyr(); + if ((mgmUpdate && susUpdate && gyrUpdate) == returnvalue::FAILED) { + return returnvalue::FAILED; + }; return returnvalue::OK; } + } // namespace ACS +// namespace ACS diff --git a/mission/controller/acs/SensorValues.h b/mission/controller/acs/SensorValues.h index daf4913c..5182215d 100644 --- a/mission/controller/acs/SensorValues.h +++ b/mission/controller/acs/SensorValues.h @@ -1,16 +1,18 @@ #ifndef SENSORVALUES_H_ #define SENSORVALUES_H_ - #include -#include "mission/devices/devicedefinitions/SusDefinitions.h" + #include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" #include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" +#include "mission/devices/devicedefinitions/GyroADIS1650XDefinitions.h" +#include "mission/devices/devicedefinitions/GyroL3GD20Definitions.h" #include "mission/devices/devicedefinitions/IMTQHandlerDefinitions.h" +#include "mission/devices/devicedefinitions/SusDefinitions.h" namespace ACS { -class SensorValues{ +class SensorValues { public: SensorValues(); virtual ~SensorValues(); @@ -18,6 +20,7 @@ class SensorValues{ ReturnValue_t update(); ReturnValue_t updateMgm(); ReturnValue_t updateSus(); + ReturnValue_t updateGyr(); MGMLIS3MDL::MgmPrimaryDataset mgm0Lis3Set = MGMLIS3MDL::MgmPrimaryDataset(objects::MGM_0_LIS3_HANDLER); @@ -44,13 +47,10 @@ class SensorValues{ SUS::SusDataset(objects::SUS_11_R_LOC_XBYMZB_PT_ZB), }; - double rmu0[3]; - double rmu1[3]; - double rmu2[3]; - - bool rmu0Valid; - bool rmu1Valid; - bool rmu2Valid; + AdisGyroPrimaryDataset gyr0AdisSet = AdisGyroPrimaryDataset(objects::GYRO_0_ADIS_HANDLER); + GyroPrimaryDataset gyr1L3gSet = GyroPrimaryDataset(objects::GYRO_1_L3G_HANDLER); + AdisGyroPrimaryDataset gyr2AdisSet = AdisGyroPrimaryDataset(objects::GYRO_2_ADIS_HANDLER); + GyroPrimaryDataset gyr3L3gSet = GyroPrimaryDataset(objects::GYRO_3_L3G_HANDLER); double quatJB[4]; // output star tracker. quaternion or dcm ? refrence to which KOS? bool quatJBValid; -- 2.34.1 From 8536c79445eb4152609ab2805155cffbddff89f9 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 11 Oct 2022 15:01:44 +0200 Subject: [PATCH 052/101] clean up --- mission/controller/AcsController.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 785a6906..e662948b 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -78,10 +78,7 @@ void AcsController::performDetumble() { ACS::SensorValues sensorValues; ACS::OutputValues outputValues; - // sensorValues.read(); - // outputValues.read(); - - timeval now; // = {0,0}; + timeval now; Clock::getClock_timeval(&now); sensorProcessing.process(&susData, now, &sensorValues, &outputValues, &acsParameters); -- 2.34.1 From d929b27c088ffee72cc7ff710bc6437977f6f852 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 12 Oct 2022 10:26:33 +0200 Subject: [PATCH 053/101] emplaced STR quaternion related dataPool. added STR dummy to acsTask --- bsp_q7s/core/InitMission.cpp | 1 + dummies/StarTrackerDummy.cpp | 24 ++++++++++++++++++++++++ 2 files changed, 25 insertions(+) diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index b502c5a4..9935f9c1 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -161,6 +161,7 @@ void initmission::initTasks() { acsTask->addComponent(objects::GYRO_1_L3G_HANDLER); acsTask->addComponent(objects::GYRO_2_ADIS_HANDLER); acsTask->addComponent(objects::GYRO_3_L3G_HANDLER); + acsTask->addComponent(objects::STAR_TRACKER); #endif PeriodicTaskIF* sysTask = factory->createPeriodicTask( diff --git a/dummies/StarTrackerDummy.cpp b/dummies/StarTrackerDummy.cpp index 8e2dd507..71f0030c 100644 --- a/dummies/StarTrackerDummy.cpp +++ b/dummies/StarTrackerDummy.cpp @@ -41,5 +41,29 @@ uint32_t StarTrackerDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) ReturnValue_t StarTrackerDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { localDataPoolMap.emplace(startracker::MCU_TEMPERATURE, new PoolEntry({0})); + + localDataPoolMap.emplace(startracker::TICKS_SOLUTION_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TIME_SOLUTION_SET, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::CALI_QW, new PoolEntry({1.0}, true)); + localDataPoolMap.emplace(startracker::CALI_QX, new PoolEntry({0.0}, true)); + localDataPoolMap.emplace(startracker::CALI_QY, new PoolEntry({0.0}, true)); + localDataPoolMap.emplace(startracker::CALI_QZ, new PoolEntry({0.0}, true)); + localDataPoolMap.emplace(startracker::TRACK_CONFIDENCE, new PoolEntry({0.0})); + localDataPoolMap.emplace(startracker::TRACK_QW, new PoolEntry({1.0})); + localDataPoolMap.emplace(startracker::TRACK_QX, new PoolEntry({0.0})); + localDataPoolMap.emplace(startracker::TRACK_QY, new PoolEntry({0.0})); + localDataPoolMap.emplace(startracker::TRACK_QZ, new PoolEntry({0.0})); + localDataPoolMap.emplace(startracker::TRACK_REMOVED, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::STARS_CENTROIDED, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::STARS_MATCHED_DATABASE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::LISA_QW, new PoolEntry({1.0})); + localDataPoolMap.emplace(startracker::LISA_QX, new PoolEntry({0.0})); + localDataPoolMap.emplace(startracker::LISA_QY, new PoolEntry({0.0})); + localDataPoolMap.emplace(startracker::LISA_QZ, new PoolEntry({0.0})); + localDataPoolMap.emplace(startracker::LISA_PERC_CLOSE, new PoolEntry({0.0})); + localDataPoolMap.emplace(startracker::LISA_NR_CLOSE, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::TRUST_WORTHY, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::STABLE_COUNT, new PoolEntry({0})); + localDataPoolMap.emplace(startracker::SOLUTION_STRATEGY, new PoolEntry({0})); return returnvalue::OK; } -- 2.34.1 From 430646afd05261fec3e666b817c1f376163f125c Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 12 Oct 2022 10:27:01 +0200 Subject: [PATCH 054/101] added STR to SensorValues --- mission/controller/acs/SensorValues.cpp | 11 ++++++++++- mission/controller/acs/SensorValues.h | 10 +++++++--- 2 files changed, 17 insertions(+), 4 deletions(-) diff --git a/mission/controller/acs/SensorValues.cpp b/mission/controller/acs/SensorValues.cpp index 3a47937a..b38a35b1 100644 --- a/mission/controller/acs/SensorValues.cpp +++ b/mission/controller/acs/SensorValues.cpp @@ -52,11 +52,20 @@ ReturnValue_t SensorValues::updateGyr() { return result; } +ReturnValue_t SensorValues::updateStr() { + ReturnValue_t result; + PoolReadGuard pgStr(&strSet); + + result = pgStr.getReadResult(); + return result; +} + ReturnValue_t SensorValues::update() { ReturnValue_t mgmUpdate = updateMgm(); ReturnValue_t susUpdate = updateSus(); ReturnValue_t gyrUpdate = updateGyr(); - if ((mgmUpdate && susUpdate && gyrUpdate) == returnvalue::FAILED) { + ReturnValue_t strUpdate = updateStr(); + if ((mgmUpdate && susUpdate && gyrUpdate && strUpdate) == returnvalue::FAILED) { return returnvalue::FAILED; }; return returnvalue::OK; diff --git a/mission/controller/acs/SensorValues.h b/mission/controller/acs/SensorValues.h index 5182215d..4e3a215f 100644 --- a/mission/controller/acs/SensorValues.h +++ b/mission/controller/acs/SensorValues.h @@ -5,6 +5,7 @@ #include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" #include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" +#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" #include "mission/devices/devicedefinitions/GyroADIS1650XDefinitions.h" #include "mission/devices/devicedefinitions/GyroL3GD20Definitions.h" #include "mission/devices/devicedefinitions/IMTQHandlerDefinitions.h" @@ -21,6 +22,7 @@ class SensorValues { ReturnValue_t updateMgm(); ReturnValue_t updateSus(); ReturnValue_t updateGyr(); + ReturnValue_t updateStr(); MGMLIS3MDL::MgmPrimaryDataset mgm0Lis3Set = MGMLIS3MDL::MgmPrimaryDataset(objects::MGM_0_LIS3_HANDLER); @@ -52,9 +54,11 @@ class SensorValues { AdisGyroPrimaryDataset gyr2AdisSet = AdisGyroPrimaryDataset(objects::GYRO_2_ADIS_HANDLER); GyroPrimaryDataset gyr3L3gSet = GyroPrimaryDataset(objects::GYRO_3_L3G_HANDLER); - double quatJB[4]; // output star tracker. quaternion or dcm ? refrence to which KOS? - bool quatJBValid; - int strIntTime[2]; + startracker::SolutionSet strSet = startracker::SolutionSet(objects::STAR_TRACKER); + + // double quatJB[4]; // output star tracker. quaternion or dcm ? refrence to which KOS? + // bool quatJBValid; + // int strIntTime[2]; double gps0latitude; // Reference is WGS84, so this one will probably be geodetic double gps0longitude; // Should be geocentric for IGRF -- 2.34.1 From 7be6bbc948d5173f6f47f5853c489ae07a93c373 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 12 Oct 2022 10:27:28 +0200 Subject: [PATCH 055/101] removed deprecated SusData input --- mission/controller/acs/SensorProcessing.cpp | 4 ++-- mission/controller/acs/SensorProcessing.h | 3 +-- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index 3c6a3564..bf9894e2 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -443,8 +443,8 @@ void SensorProcessing::processGps(const double gps0latitude, const double gps0lo } } -void SensorProcessing::process(acsctrl::SusDataRaw *susData, timeval now, - ACS::SensorValues *sensorValues, ACS::OutputValues *outputValues, +void SensorProcessing::process(timeval now, ACS::SensorValues *sensorValues, + ACS::OutputValues *outputValues, const AcsParameters *acsParameters) { sensorValues->update(); // processGps(sensorValues->gps0latitude, sensorValues->gps0longitude, sensorValues->gps0Valid, diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h index 609c6e6a..50b78238 100644 --- a/mission/controller/acs/SensorProcessing.h +++ b/mission/controller/acs/SensorProcessing.h @@ -23,8 +23,7 @@ class SensorProcessing { SensorProcessing(AcsParameters *acsParameters_); virtual ~SensorProcessing(); - void process(acsctrl::SusDataRaw *susData, timeval now, ACS::SensorValues *sensorValues, - ACS::OutputValues *outputValues, + void process(timeval now, ACS::SensorValues *sensorValues, ACS::OutputValues *outputValues, const AcsParameters *acsParameters); // Will call protected functions private: protected: -- 2.34.1 From 4aecd079707b9f76a899d9e9ba46c45e4e821636 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 12 Oct 2022 10:28:44 +0200 Subject: [PATCH 056/101] added PtgCtrl code. matched inputs to actual SensorValues inputs --- mission/controller/AcsController.cpp | 40 ++++++++++++++-- mission/controller/AcsController.h | 5 ++ mission/controller/acs/Navigation.cpp | 69 ++++++++++++++------------- 3 files changed, 75 insertions(+), 39 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index e662948b..84a7682f 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -1,14 +1,15 @@ #include "AcsController.h" #include -//#include AcsController::AcsController(object_id_t objectId) : ExtendedControllerBase(objectId, objects::NO_OBJECT), sensorProcessing(&acsParameters), navigation(&acsParameters), actuatorCmd(&acsParameters), + guidance(&acsParameters), detumble(&acsParameters), + ptgCtrl(&acsParameters), detumbleCounter{0}, mgmData(this), susData(this) {} @@ -42,7 +43,7 @@ void AcsController::performControlOperation() { break; case SUBMODE_PTG_GS: - // performPointingCtrl(); + performPointingCtrl(); break; } } @@ -65,7 +66,6 @@ void AcsController::performControlOperation() { } } - // DEBUG : REMOVE AFTER COMPLETION mode = MODE_ON; submode = SUBMODE_DETUMBLE; @@ -81,7 +81,7 @@ void AcsController::performDetumble() { timeval now; Clock::getClock_timeval(&now); - sensorProcessing.process(&susData, now, &sensorValues, &outputValues, &acsParameters); + sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); ReturnValue_t validMekf; navigation.useMekf(&sensorValues, &outputValues, &validMekf); double magMomMtq[3] = {0, 0, 0}; @@ -108,7 +108,37 @@ void AcsController::performDetumble() { } } -void AcsController::performPointingCtrl() {} +void AcsController::performPointingCtrl() { + ACS::SensorValues sensorValues; + ACS::OutputValues outputValues; + + timeval now; // Übergabe ? + + sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); + ReturnValue_t validMekf; + navigation.useMekf(&sensorValues, &outputValues, &validMekf); + double targetQuat[4] = {0, 0, 0, 0}, refSatRate[3] = {0, 0, 0}; + guidance.targetQuatPtg(&sensorValues, &outputValues, now, targetQuat, refSatRate); + double quatError[3] = {0, 0, 0}, deltaRate[3] = {0, 0, 0}; + guidance.comparePtg(targetQuat, &outputValues, refSatRate, quatError, deltaRate); + double rwPseudoInv[4][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + guidance.getDistributionMatrixRw(&sensorValues, *rwPseudoInv); + double torquePtgRws[4] = {0, 0, 0, 0}, mode = 0; + ptgCtrl.ptgGroundstation(mode, quatError, deltaRate, *rwPseudoInv, torquePtgRws); + double rwTrqNs[4] = {0, 0, 0, 0}; + ptgCtrl.ptgNullspace(&(sensorValues.speedRw0), &(sensorValues.speedRw1), &(sensorValues.speedRw2), + &(sensorValues.speedRw3), rwTrqNs); + double cmdSpeedRws[4] = {0, 0, 0, 0}; // Should be given to the actuator reaction wheel as input + actuatorCmd.cmdSpeedToRws(&(sensorValues.speedRw0), &(sensorValues.speedRw1), + &(sensorValues.speedRw2), &(sensorValues.speedRw3), torquePtgRws, + rwTrqNs, cmdSpeedRws); + double mgtDpDes[3] = {0, 0, 0}, dipolUnits[3] = {0, 0, 0}; // Desaturation Dipol + ptgCtrl.ptgDesaturation(outputValues.magFieldEst, &outputValues.magFieldEstValid, + outputValues.satRateMekf, &(sensorValues.speedRw0), + &(sensorValues.speedRw1), &(sensorValues.speedRw2), + &(sensorValues.speedRw3), mgtDpDes); + actuatorCmd.cmdDipolMtq(mgtDpDes, dipolUnits); +} ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index fa4ba88e..c23adfc1 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -6,9 +6,11 @@ #include #include "acs/ActuatorCmd.h" +#include "acs/Guidance.h" #include "acs/Navigation.h" #include "acs/SensorProcessing.h" #include "acs/control/Detumble.h" +#include "acs/control/PtgCtrl.h" #include "controllerdefinitions/AcsCtrlDefinitions.h" #include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" #include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" @@ -37,8 +39,11 @@ class AcsController : public ExtendedControllerBase { SensorProcessing sensorProcessing; Navigation navigation; ActuatorCmd actuatorCmd; + Guidance guidance; Detumble detumble; + PtgCtrl ptgCtrl; + uint8_t detumbleCounter; enum class InternalState { STARTUP, INITIAL_DELAY, READY }; diff --git a/mission/controller/acs/Navigation.cpp b/mission/controller/acs/Navigation.cpp index a2e3aa5d..deb50aa1 100644 --- a/mission/controller/acs/Navigation.cpp +++ b/mission/controller/acs/Navigation.cpp @@ -6,45 +6,46 @@ */ #include "Navigation.h" -#include "util/MathOperations.h" -#include "util/CholeskyDecomposition.h" -#include -#include + #include #include +#include +#include +#include "util/CholeskyDecomposition.h" +#include "util/MathOperations.h" -Navigation::Navigation(AcsParameters *acsParameters_): multiplicativeKalmanFilter(acsParameters_){ - acsParameters = *acsParameters_; +Navigation::Navigation(AcsParameters *acsParameters_) : multiplicativeKalmanFilter(acsParameters_) { + acsParameters = *acsParameters_; } -Navigation::~Navigation(){ +Navigation::~Navigation() {} +void Navigation::useMekf(ACS::SensorValues *sensorValues, ACS::OutputValues *outputValues, + ReturnValue_t *mekfValid) { + double quatJB[4] = {sensorValues->strSet.caliQx.value, sensorValues->strSet.caliQy.value, + sensorValues->strSet.caliQz.value, sensorValues->strSet.caliQw.value}; + bool quatJBValid = + (sensorValues->strSet.caliQx.isValid() && sensorValues->strSet.caliQy.isValid() && + sensorValues->strSet.caliQz.isValid() && sensorValues->strSet.caliQw.isValid()); + + if (kalmanInit) { + *mekfValid = multiplicativeKalmanFilter.mekfEst( + quatJB, &quatJBValid, outputValues->satRateEst, &outputValues->satRateEstValid, + outputValues->magFieldEst, &outputValues->magFieldEstValid, outputValues->sunDirEst, + &outputValues->sunDirEstValid, outputValues->sunDirModel, &outputValues->sunDirModelValid, + outputValues->magFieldModel, &outputValues->magFieldModelValid, outputValues->quatMekfBJ, + outputValues->satRateMekf); // VALIDS FOR QUAT AND RATE ?? + } + else { + multiplicativeKalmanFilter.init(outputValues->magFieldEst, &outputValues->magFieldEstValid, + outputValues->sunDirEst, &outputValues->sunDirEstValid, + outputValues->sunDirModel, &outputValues->sunDirModelValid, + outputValues->magFieldModel, &outputValues->magFieldModelValid); + kalmanInit = true; + *mekfValid = 0; + + // Maybe we need feedback from kalmanfilter to identify if there was a problem with the init + //of kalman filter where does this class know from that kalman filter was not initialized ? + } } - -void Navigation::useMekf(ACS::SensorValues* sensorValues, ACS::OutputValues *outputValues, ReturnValue_t *mekfValid){ - - if (kalmanInit) { - *mekfValid = multiplicativeKalmanFilter.mekfEst(sensorValues->quatJB, &sensorValues->quatJBValid, - outputValues->satRateEst, &outputValues->satRateEstValid, - outputValues->magFieldEst, &outputValues->magFieldEstValid, - outputValues->sunDirEst, &outputValues->sunDirEstValid, - outputValues->sunDirModel, &outputValues->sunDirModelValid, - outputValues->magFieldModel, &outputValues->magFieldModelValid, - outputValues->quatMekfBJ, outputValues->satRateMekf); // VALIDS FOR QUAT AND RATE ?? - - } - else { - multiplicativeKalmanFilter.init(outputValues->magFieldEst, &outputValues->magFieldEstValid, - outputValues->sunDirEst, &outputValues->sunDirEstValid, - outputValues->sunDirModel, &outputValues->sunDirModelValid, - outputValues->magFieldModel, &outputValues->magFieldModelValid); - kalmanInit = true; - *mekfValid = 0; - -// Maybe we need feedback from kalmanfilter to identify if there was a problem with the init of kalman filter -// where does this class know from that kalman filter was not initialized ? - } -} - - -- 2.34.1 From 2a9dc518a0693bda9fdf0d863c7c551a47da864c Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 12 Oct 2022 15:04:19 +0200 Subject: [PATCH 057/101] added GpsDummy --- bsp_q7s/core/InitMission.cpp | 1 + dummies/CMakeLists.txt | 1 + dummies/GpsDummy.cpp | 56 ++++++++++++++++++++++++++++++++++++ dummies/GpsDummy.h | 33 +++++++++++++++++++++ dummies/helpers.cpp | 6 ++-- 5 files changed, 95 insertions(+), 2 deletions(-) create mode 100644 dummies/GpsDummy.cpp create mode 100644 dummies/GpsDummy.h diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index 9935f9c1..e3e26be9 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -161,6 +161,7 @@ void initmission::initTasks() { acsTask->addComponent(objects::GYRO_1_L3G_HANDLER); acsTask->addComponent(objects::GYRO_2_ADIS_HANDLER); acsTask->addComponent(objects::GYRO_3_L3G_HANDLER); + acsTask->addComponent(objects::GPS_CONTROLLER); acsTask->addComponent(objects::STAR_TRACKER); #endif diff --git a/dummies/CMakeLists.txt b/dummies/CMakeLists.txt index 4cb05289..3c46736f 100644 --- a/dummies/CMakeLists.txt +++ b/dummies/CMakeLists.txt @@ -12,6 +12,7 @@ target_sources( AcuDummy.cpp PduDummy.cpp P60DockDummy.cpp + GpsDummy.cpp GyroAdisDummy.cpp GyroL3GD20Dummy.cpp MgmLIS3MDLDummy.cpp diff --git a/dummies/GpsDummy.cpp b/dummies/GpsDummy.cpp new file mode 100644 index 00000000..d1f526d2 --- /dev/null +++ b/dummies/GpsDummy.cpp @@ -0,0 +1,56 @@ +#include "GpsDummy.h" + +#include + +GpsDummy::GpsDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie) {} + +GpsDummy::~GpsDummy() {} + +void GpsDummy::doStartUp() {} + +void GpsDummy::doShutDown() {} + +ReturnValue_t GpsDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; } + +ReturnValue_t GpsDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; +} + +ReturnValue_t GpsDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, size_t commandDataLen) { + return returnvalue::OK; +} + +ReturnValue_t GpsDummy::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) { + return returnvalue::OK; +} + +ReturnValue_t GpsDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { + return returnvalue::OK; +} + +void GpsDummy::fillCommandAndReplyMap() {} + +uint32_t GpsDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t GpsDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(GpsHyperion::LATITUDE, new PoolEntry({0.0})); + localDataPoolMap.emplace(GpsHyperion::LONGITUDE, new PoolEntry({0.0})); + localDataPoolMap.emplace(GpsHyperion::ALTITUDE, new PoolEntry({0.0})); + localDataPoolMap.emplace(GpsHyperion::SPEED, new PoolEntry({7684.2})); + localDataPoolMap.emplace(GpsHyperion::FIX_MODE, new PoolEntry({0})); + localDataPoolMap.emplace(GpsHyperion::SATS_IN_USE, new PoolEntry({0})); + localDataPoolMap.emplace(GpsHyperion::SATS_IN_VIEW, new PoolEntry({0})); + localDataPoolMap.emplace(GpsHyperion::YEAR, new PoolEntry({0})); + localDataPoolMap.emplace(GpsHyperion::MONTH, new PoolEntry({0})); + localDataPoolMap.emplace(GpsHyperion::DAY, new PoolEntry({0})); + localDataPoolMap.emplace(GpsHyperion::HOURS, new PoolEntry({0})); + localDataPoolMap.emplace(GpsHyperion::MINUTES, new PoolEntry({0})); + localDataPoolMap.emplace(GpsHyperion::SECONDS, new PoolEntry({0})); + localDataPoolMap.emplace(GpsHyperion::UNIX_SECONDS, new PoolEntry({0})); + + return returnvalue::OK; +} diff --git a/dummies/GpsDummy.h b/dummies/GpsDummy.h new file mode 100644 index 00000000..b32b7f17 --- /dev/null +++ b/dummies/GpsDummy.h @@ -0,0 +1,33 @@ +#ifndef DUMMIES_GPSDUMMY_H_ +#define DUMMIES_GPSDUMMY_H_ + +#include + +class GpsDummy : public DeviceHandlerBase { + public: + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; + + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + GpsDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~GpsDummy(); + + protected: + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; +}; + +#endif /* DUMMIES_GPSDUMMY_H_ */ diff --git a/dummies/helpers.cpp b/dummies/helpers.cpp index 46cf207d..74410f56 100644 --- a/dummies/helpers.cpp +++ b/dummies/helpers.cpp @@ -1,10 +1,9 @@ -#include "helpers.h" - #include #include #include #include #include +#include #include #include #include @@ -18,6 +17,8 @@ #include #include +#include "helpers.h" + using namespace dummy; void dummy::createDummies(DummyCfg cfg) { @@ -51,6 +52,7 @@ void dummy::createDummies(DummyCfg cfg) { new MgmLIS3MDLDummy(objects::MGM_2_LIS3_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); new MgmRm3100Dummy(objects::MGM_1_RM3100_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); new MgmRm3100Dummy(objects::MGM_3_RM3100_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); + new GpsDummy(objects::GPS_CONTROLLER, objects::DUMMY_COM_IF, comCookieDummy); } if (cfg.addSusDummies) { -- 2.34.1 From 84fc44fd5fcf9d7794f2c5bf222be52fda130430 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 12 Oct 2022 15:06:24 +0200 Subject: [PATCH 058/101] fixed GPS and STR inputs --- mission/controller/AcsController.cpp | 20 +- mission/controller/acs/ActuatorCmd.cpp | 61 +-- mission/controller/acs/ActuatorCmd.h | 7 +- mission/controller/acs/Guidance.cpp | 558 ++++++++++---------- mission/controller/acs/SensorProcessing.cpp | 4 +- mission/controller/acs/SensorValues.cpp | 17 + mission/controller/acs/SensorValues.h | 44 +- mission/controller/acs/control/PtgCtrl.cpp | 94 ++-- mission/controller/acs/control/PtgCtrl.h | 67 +-- 9 files changed, 434 insertions(+), 438 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 84a7682f..856a0034 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -126,17 +126,19 @@ void AcsController::performPointingCtrl() { double torquePtgRws[4] = {0, 0, 0, 0}, mode = 0; ptgCtrl.ptgGroundstation(mode, quatError, deltaRate, *rwPseudoInv, torquePtgRws); double rwTrqNs[4] = {0, 0, 0, 0}; - ptgCtrl.ptgNullspace(&(sensorValues.speedRw0), &(sensorValues.speedRw1), &(sensorValues.speedRw2), - &(sensorValues.speedRw3), rwTrqNs); + ptgCtrl.ptgNullspace( + &(sensorValues.rw1Set.currSpeed.value), &(sensorValues.rw2Set.currSpeed.value), + &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), rwTrqNs); double cmdSpeedRws[4] = {0, 0, 0, 0}; // Should be given to the actuator reaction wheel as input - actuatorCmd.cmdSpeedToRws(&(sensorValues.speedRw0), &(sensorValues.speedRw1), - &(sensorValues.speedRw2), &(sensorValues.speedRw3), torquePtgRws, - rwTrqNs, cmdSpeedRws); + actuatorCmd.cmdSpeedToRws( + &(sensorValues.rw1Set.currSpeed.value), &(sensorValues.rw2Set.currSpeed.value), + &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), torquePtgRws, + rwTrqNs, cmdSpeedRws); double mgtDpDes[3] = {0, 0, 0}, dipolUnits[3] = {0, 0, 0}; // Desaturation Dipol - ptgCtrl.ptgDesaturation(outputValues.magFieldEst, &outputValues.magFieldEstValid, - outputValues.satRateMekf, &(sensorValues.speedRw0), - &(sensorValues.speedRw1), &(sensorValues.speedRw2), - &(sensorValues.speedRw3), mgtDpDes); + ptgCtrl.ptgDesaturation( + outputValues.magFieldEst, &outputValues.magFieldEstValid, outputValues.satRateMekf, + &(sensorValues.rw1Set.currSpeed.value), &(sensorValues.rw2Set.currSpeed.value), + &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), mgtDpDes); actuatorCmd.cmdDipolMtq(mgtDpDes, dipolUnits); } diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index 261277a0..920989ed 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -23,42 +23,37 @@ ActuatorCmd::~ActuatorCmd(){ } -void ActuatorCmd::cmdSpeedToRws(const double *speedRw0, const double *speedRw1, const double *speedRw2, - const double *speedRw3, const double *rwTrqIn, const double *rwTrqNS, double *rwCmdSpeed){ - - using namespace Math; - // Scaling the commanded torque to a maximum value - double torque[4] = {0, 0, 0, 0}; - double maxTrq = acsParameters.rwHandlingParameters.maxTrq; - VectorOperations::add(rwTrqIn, rwTrqNS, torque, 4); - - double maxValue = 0; - for (int i = 0; i < 4; i++) { //size of torque, always 4 ? - if (abs(torque[i]) > maxValue) { - maxValue = abs(torque[i]); - } - } - - if (maxValue > maxTrq) { - - double scalingFactor = maxTrq / maxValue; - VectorOperations::mulScalar(torque, scalingFactor, torque, 4); - - } - - // Calculating the commanded speed in RPM for every reaction wheel - double 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; - VectorOperations::mulScalar(torque, factor, deltaSpeed, 4); - VectorOperations::add(speedRws, deltaSpeed, rwCmdSpeed, 4); +void ActuatorCmd::cmdSpeedToRws(const int32_t *speedRw0, const int32_t *speedRw1, + const int32_t *speedRw2, const int32_t *speedRw3, + const double *rwTrqIn, const double *rwTrqNS, double *rwCmdSpeed) { + using namespace Math; + // Scaling the commanded torque to a maximum value + double torque[4] = {0, 0, 0, 0}; + double maxTrq = acsParameters.rwHandlingParameters.maxTrq; + VectorOperations::add(rwTrqIn, rwTrqNS, torque, 4); + double maxValue = 0; + for (int i = 0; i < 4; i++) { // size of torque, always 4 ? + if (abs(torque[i]) > maxValue) { + maxValue = abs(torque[i]); + } + } + if (maxValue > maxTrq) { + double scalingFactor = maxTrq / maxValue; + VectorOperations::mulScalar(torque, scalingFactor, torque, 4); + } + // Calculating the commanded speed in RPM for every reaction wheel + double 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; + VectorOperations::mulScalar(torque, factor, deltaSpeed, 4); + VectorOperations::add(speedRws, deltaSpeed, rwCmdSpeed, 4); } void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, double *dipolMomentUnits) { diff --git a/mission/controller/acs/ActuatorCmd.h b/mission/controller/acs/ActuatorCmd.h index 820f1f00..1da2c89a 100644 --- a/mission/controller/acs/ActuatorCmd.h +++ b/mission/controller/acs/ActuatorCmd.h @@ -28,10 +28,11 @@ public: * rwTrqNS Nullspace torque * rwCmdSpeed output revolutions per minute for every reaction wheel */ - void cmdSpeedToRws(const double *speedRw0, const double *speedRw1, const double *speedRw2, const double *speedRw3, - const double *rwTrqIn, const double *rwTrqNS, double *rwCmdSpeed); + void cmdSpeedToRws(const int32_t *speedRw0, const int32_t *speedRw1, + const int32_t *speedRw2, const int32_t *speedRw3, const double *rwTrqIn, + const double *rwTrqNS, double *rwCmdSpeed); - /* + /* * @brief: cmdDipolMtq() gives the commanded dipol moment for the magnetorques * * @param: dipolMoment given dipol moment in spacecraft frame diff --git a/mission/controller/acs/Guidance.cpp b/mission/controller/acs/Guidance.cpp index 7d9cd8df..f6ebee5f 100644 --- a/mission/controller/acs/Guidance.cpp +++ b/mission/controller/acs/Guidance.cpp @@ -5,343 +5,323 @@ * Author: Robin Marquardt */ - #include "Guidance.h" -#include "string.h" -#include "util/MathOperations.h" -#include "util/CholeskyDecomposition.h" -#include -#include + #include #include +#include +#include -Guidance::Guidance(AcsParameters *acsParameters_) { - acsParameters = *acsParameters_; +#include "string.h" +#include "util/CholeskyDecomposition.h" +#include "util/MathOperations.h" -} +Guidance::Guidance(AcsParameters *acsParameters_) { acsParameters = *acsParameters_; } -Guidance::~Guidance() { - -} +Guidance::~Guidance() {} void Guidance::getTargetParamsSafe(double sunTargetSafe[3], double satRateSafe[3]) { + for (int i = 0; i < 3; i++) { + sunTargetSafe[i] = acsParameters.safeModeControllerParameters.sunTargetDir[i]; + satRateSafe[i] = acsParameters.safeModeControllerParameters.satRateRef[i]; + } - for (int i = 0; i < 3; i++) { - - sunTargetSafe[i] = - acsParameters.safeModeControllerParameters.sunTargetDir[i]; - satRateSafe[i] = - acsParameters.safeModeControllerParameters.satRateRef[i]; - - } - - -// memcpy(sunTargetSafe, acsParameters.safeModeControllerParameters.sunTargetDir, 24); - + // memcpy(sunTargetSafe, acsParameters.safeModeControllerParameters.sunTargetDir, 24); } -void Guidance::targetQuatPtg(ACS::SensorValues* sensorValues, ACS::OutputValues *outputValues, - timeval now, double targetQuat[4], double refSatRate[3]){ -//------------------------------------------------------------------------------------- -// Calculation of target quaternion to groundstation -//------------------------------------------------------------------------------------- -// Transform longitude, latitude and altitude of groundstation to cartesian coordiantes (earth fixed/centered frame) - double groundStationCart[3] = {0, 0, 0}; +void Guidance::targetQuatPtg(ACS::SensorValues *sensorValues, ACS::OutputValues *outputValues, + timeval now, double targetQuat[4], double refSatRate[3]) { + //------------------------------------------------------------------------------------- + // Calculation of target quaternion to groundstation + //------------------------------------------------------------------------------------- + // Transform longitude, latitude and altitude of groundstation to cartesian coordiantes (earth + // fixed/centered frame) + double groundStationCart[3] = {0, 0, 0}; - MathOperations::cartesianFromLatLongAlt(acsParameters.groundStationParameters.latitudeGs, - acsParameters.groundStationParameters.longitudeGs, acsParameters.groundStationParameters.altitudeGs, - groundStationCart); + MathOperations::cartesianFromLatLongAlt(acsParameters.groundStationParameters.latitudeGs, + acsParameters.groundStationParameters.longitudeGs, + acsParameters.groundStationParameters.altitudeGs, + groundStationCart); -// Position of the satellite in the earth/fixed frame via GPS - double posSatE[3] = {0, 0, 0}; - MathOperations::cartesianFromLatLongAlt(sensorValues->gps0latitude, sensorValues->gps0longitude, - sensorValues->gps0altitude, posSatE); + // Position of the satellite in the earth/fixed frame via GPS + double posSatE[3] = {0, 0, 0}; + MathOperations::cartesianFromLatLongAlt(sensorValues->gpsSet.latitude.value, + sensorValues->gpsSet.longitude.value, + sensorValues->gpsSet.altitude.value, posSatE); -// Target direction in the ECEF frame - double targetDirE[3] = {0, 0, 0}; - VectorOperations::subtract(groundStationCart, posSatE, targetDirE, 3); + // Target direction in the ECEF frame + double targetDirE[3] = {0, 0, 0}; + VectorOperations::subtract(groundStationCart, posSatE, targetDirE, 3); -// Transformation between ECEF and IJK frame - double dcmEJ[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - double dcmJE[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - MathOperations::dcmEJ(now, *dcmEJ); - MathOperations::inverseMatrixDimThree(*dcmEJ, *dcmJE); -// Derivative of dmcEJ WITHOUT PRECISSION AND NUTATION - double dcmEJDot[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - double dcmJEDot[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - double dcmDot[3][3] = {{0, 1, 0}, {-1, 0, 0}, {0, 0, 0}}; - double omegaEarth = acsParameters.targetModeControllerParameters.omegaEarth; + // Transformation between ECEF and IJK frame + double dcmEJ[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double dcmJE[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MathOperations::dcmEJ(now, *dcmEJ); + MathOperations::inverseMatrixDimThree(*dcmEJ, *dcmJE); + // Derivative of dmcEJ WITHOUT PRECISSION AND NUTATION + double dcmEJDot[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double dcmJEDot[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double dcmDot[3][3] = {{0, 1, 0}, {-1, 0, 0}, {0, 0, 0}}; + double omegaEarth = acsParameters.targetModeControllerParameters.omegaEarth; -// TEST SECTION ! - //double dcmTEST[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - //MatrixOperations::multiply(&acsParameters.magnetorquesParameter.mtq0orientationMatrix, dcmTEST, dcmTEST, 3, 3, 3); + // TEST SECTION ! + // double dcmTEST[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + // MatrixOperations::multiply(&acsParameters.magnetorquesParameter.mtq0orientationMatrix, + // dcmTEST, dcmTEST, 3, 3, 3); - MatrixOperations::multiply(*dcmDot, *dcmEJ, *dcmEJDot, 3, 3, 3); - MatrixOperations::multiplyScalar(*dcmEJDot, omegaEarth, *dcmEJDot, 3, 3); - MathOperations::inverseMatrixDimThree(*dcmEJDot, *dcmJEDot); + MatrixOperations::multiply(*dcmDot, *dcmEJ, *dcmEJDot, 3, 3, 3); + MatrixOperations::multiplyScalar(*dcmEJDot, omegaEarth, *dcmEJDot, 3, 3); + MathOperations::inverseMatrixDimThree(*dcmEJDot, *dcmJEDot); -// Transformation between ECEF and Body frame - double dcmBJ[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - double dcmBE[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - double quatBJ[4] = {0, 0, 0, 0}; - quatBJ[0] = outputValues->quatMekfBJ[0]; - quatBJ[1] = outputValues->quatMekfBJ[1]; - quatBJ[2] = outputValues->quatMekfBJ[2]; - quatBJ[3] = outputValues->quatMekfBJ[3]; - QuaternionOperations::toDcm(quatBJ, dcmBJ); - MatrixOperations::multiply(*dcmBJ, *dcmJE, *dcmBE, 3, 3, 3); + // Transformation between ECEF and Body frame + double dcmBJ[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double dcmBE[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double quatBJ[4] = {0, 0, 0, 0}; + quatBJ[0] = outputValues->quatMekfBJ[0]; + quatBJ[1] = outputValues->quatMekfBJ[1]; + quatBJ[2] = outputValues->quatMekfBJ[2]; + quatBJ[3] = outputValues->quatMekfBJ[3]; + QuaternionOperations::toDcm(quatBJ, dcmBJ); + MatrixOperations::multiply(*dcmBJ, *dcmJE, *dcmBE, 3, 3, 3); -// Target Direction in the body frame - double targetDirB[3] = {0, 0, 0}; - MatrixOperations::multiply(*dcmBE, targetDirE, targetDirB, 3, 3, 1); + // Target Direction in the body frame + double targetDirB[3] = {0, 0, 0}; + MatrixOperations::multiply(*dcmBE, targetDirE, targetDirB, 3, 3, 1); -// 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]; - double noramlizedTargetDirB[3] = {0, 0, 0}; - VectorOperations::normalize(targetDirB, noramlizedTargetDirB, 3); - VectorOperations::normalize(refDir, refDir, 3); - double normTargetDirB = VectorOperations::norm(noramlizedTargetDirB, 3); - double normRefDir = VectorOperations::norm(refDir, 3); - double crossDir[3] = {0, 0, 0}; - double dotDirections = VectorOperations::dot(noramlizedTargetDirB, refDir); - VectorOperations::cross(noramlizedTargetDirB, refDir, crossDir); - targetQuat[0] = crossDir[0]; - targetQuat[1] = crossDir[1]; - targetQuat[2] = crossDir[2]; - targetQuat[3] = sqrt(pow(normTargetDirB,2) * pow(normRefDir,2) + dotDirections); - VectorOperations::normalize(targetQuat, targetQuat, 4); + // 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]; + double noramlizedTargetDirB[3] = {0, 0, 0}; + VectorOperations::normalize(targetDirB, noramlizedTargetDirB, 3); + VectorOperations::normalize(refDir, refDir, 3); + double normTargetDirB = VectorOperations::norm(noramlizedTargetDirB, 3); + double normRefDir = VectorOperations::norm(refDir, 3); + double crossDir[3] = {0, 0, 0}; + double dotDirections = VectorOperations::dot(noramlizedTargetDirB, refDir); + VectorOperations::cross(noramlizedTargetDirB, refDir, crossDir); + targetQuat[0] = crossDir[0]; + targetQuat[1] = crossDir[1]; + targetQuat[2] = crossDir[2]; + targetQuat[3] = sqrt(pow(normTargetDirB, 2) * pow(normRefDir, 2) + dotDirections); + VectorOperations::normalize(targetQuat, targetQuat, 4); -//------------------------------------------------------------------------------------- -// Calculation of reference rotation rate -//------------------------------------------------------------------------------------- - double velSatE[3] = {0, 0, 0}; - velSatE[0] = sensorValues->gps0Velocity[0]; - velSatE[1] = sensorValues->gps0Velocity[1]; - velSatE[2] = sensorValues->gps0Velocity[2]; - double velSatB[3] = {0, 0, 0}, velSatBPart1[3] = {0, 0, 0}, - velSatBPart2[3] = {0, 0, 0}; -// Velocity: v_B = dcm_BI * dcmIE * v_E + dcm_BI * DotDcm_IE * v_E - MatrixOperations::multiply(*dcmBE, velSatE, velSatBPart1, 3, 3, 1); - double dcmBEDot[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - MatrixOperations::multiply(*dcmBJ, *dcmJEDot, *dcmBEDot, 3, 3, 3); - MatrixOperations::multiply(*dcmBEDot, posSatE, velSatBPart2, 3, 3, 1); - VectorOperations::add(velSatBPart1, velSatBPart2, velSatB, 3); + //------------------------------------------------------------------------------------- + // Calculation of reference rotation rate + //------------------------------------------------------------------------------------- + double velSatE[3] = {0, 0, 0}; + velSatE[0] = 0.0; // sensorValues->gps0Velocity[0]; + velSatE[1] = 0.0; // sensorValues->gps0Velocity[1]; + velSatE[2] = 0.0; // sensorValues->gps0Velocity[2]; + double velSatB[3] = {0, 0, 0}, velSatBPart1[3] = {0, 0, 0}, velSatBPart2[3] = {0, 0, 0}; + // Velocity: v_B = dcm_BI * dcmIE * v_E + dcm_BI * DotDcm_IE * v_E + MatrixOperations::multiply(*dcmBE, velSatE, velSatBPart1, 3, 3, 1); + double dcmBEDot[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MatrixOperations::multiply(*dcmBJ, *dcmJEDot, *dcmBEDot, 3, 3, 3); + MatrixOperations::multiply(*dcmBEDot, posSatE, velSatBPart2, 3, 3, 1); + VectorOperations::add(velSatBPart1, velSatBPart2, velSatB, 3); - double normVelSatB = VectorOperations::norm(velSatB, 3); - double normRefSatRate = normVelSatB / normTargetDirB; + double normVelSatB = VectorOperations::norm(velSatB, 3); + double normRefSatRate = normVelSatB / normTargetDirB; - double satRateDir[3] = {0, 0, 0}; - VectorOperations::cross(velSatB, targetDirB, satRateDir); - VectorOperations::normalize(satRateDir, satRateDir, 3); - VectorOperations::mulScalar(satRateDir, normRefSatRate, refSatRate, 3); + double satRateDir[3] = {0, 0, 0}; + VectorOperations::cross(velSatB, targetDirB, satRateDir); + VectorOperations::normalize(satRateDir, satRateDir, 3); + VectorOperations::mulScalar(satRateDir, normRefSatRate, refSatRate, 3); -//------------------------------------------------------------------------------------- -// Calculation of reference rotation rate in case of star tracker blinding -//------------------------------------------------------------------------------------- - if ( acsParameters.targetModeControllerParameters.avoidBlindStr ) { + //------------------------------------------------------------------------------------- + // Calculation of reference rotation rate in case of star tracker blinding + //------------------------------------------------------------------------------------- + if (acsParameters.targetModeControllerParameters.avoidBlindStr) { + double sunDirJ[3] = {0, 0, 0}; + double sunDirB[3] = {0, 0, 0}; - double sunDirJ[3] = {0, 0, 0}; - double sunDirB[3] = {0, 0, 0}; + if (outputValues->sunDirModelValid) { + sunDirJ[0] = outputValues->sunDirModel[0]; + sunDirJ[1] = outputValues->sunDirModel[1]; + sunDirJ[2] = outputValues->sunDirModel[2]; + MatrixOperations::multiply(*dcmBJ, sunDirJ, sunDirB, 3, 3, 1); + } - if ( outputValues->sunDirModelValid ) { + else { + sunDirB[0] = outputValues->sunDirEst[0]; + sunDirB[1] = outputValues->sunDirEst[1]; + sunDirB[2] = outputValues->sunDirEst[2]; + } - sunDirJ[0] = outputValues->sunDirModel[0]; - sunDirJ[1] = outputValues->sunDirModel[1]; - sunDirJ[2] = outputValues->sunDirModel[2]; - MatrixOperations::multiply(*dcmBJ, sunDirJ, sunDirB, 3, 3, 1); - } + double exclAngle = acsParameters.strParameters.exclusionAngle, + blindStart = acsParameters.targetModeControllerParameters.blindAvoidStart, + blindEnd = acsParameters.targetModeControllerParameters.blindAvoidStop; - else { - sunDirB[0] = outputValues->sunDirEst[0]; - sunDirB[1] = outputValues->sunDirEst[1]; - sunDirB[2] = outputValues->sunDirEst[2]; + double sightAngleSun = + VectorOperations::dot(acsParameters.strParameters.boresightAxis, sunDirB); - } + if (!(strBlindAvoidFlag)) { + double critSightAngle = blindStart * exclAngle; - double exclAngle = acsParameters.strParameters.exclusionAngle, - blindStart = acsParameters.targetModeControllerParameters.blindAvoidStart, - blindEnd = acsParameters.targetModeControllerParameters.blindAvoidStop; + if (sightAngleSun < critSightAngle) { + strBlindAvoidFlag = true; + } - double sightAngleSun = VectorOperations::dot(acsParameters.strParameters.boresightAxis, sunDirB); + } - if ( !(strBlindAvoidFlag) ) { + else { + if (sightAngleSun < blindEnd * exclAngle) { + double normBlindRefRate = acsParameters.targetModeControllerParameters.blindRotRate; + double blindRefRate[3] = {0, 0, 0}; - double critSightAngle = blindStart * exclAngle; + if (sunDirB[1] < 0) { + blindRefRate[0] = normBlindRefRate; + blindRefRate[1] = 0; + blindRefRate[2] = 0; + } else { + blindRefRate[0] = -normBlindRefRate; + blindRefRate[1] = 0; + blindRefRate[2] = 0; + } - if ( sightAngleSun < critSightAngle) { - strBlindAvoidFlag = true; - } + VectorOperations::add(blindRefRate, refSatRate, refSatRate, 3); - } - - else { - if ( sightAngleSun < blindEnd * exclAngle) { - - double normBlindRefRate = acsParameters.targetModeControllerParameters.blindRotRate; - double blindRefRate[3] = {0, 0, 0}; - - - if ( sunDirB[1] < 0) { - blindRefRate[0] = normBlindRefRate; - blindRefRate[1] = 0; - blindRefRate[2] = 0; - } - else { - blindRefRate[0] = -normBlindRefRate; - blindRefRate[1] = 0; - blindRefRate[2] = 0; - } - - VectorOperations::add(blindRefRate, refSatRate, refSatRate, 3); - - } - else { - strBlindAvoidFlag = false; - } - } - } + } else { + strBlindAvoidFlag = false; + } + } + } } +void Guidance::comparePtg(double targetQuat[4], ACS::OutputValues *outputValues, + double refSatRate[3], double quatError[3], double deltaRate[3]) { + double quatRef[4] = {0, 0, 0, 0}; + quatRef[0] = acsParameters.targetModeControllerParameters.quatRef[0]; + quatRef[1] = acsParameters.targetModeControllerParameters.quatRef[1]; + quatRef[2] = acsParameters.targetModeControllerParameters.quatRef[2]; + quatRef[3] = acsParameters.targetModeControllerParameters.quatRef[3]; -void Guidance::comparePtg(double targetQuat[4], ACS::OutputValues *outputValues, double refSatRate[3], double quatError[3], double deltaRate[3] ) { + double satRate[3] = {0, 0, 0}; + satRate[0] = outputValues->satRateMekf[0]; + satRate[1] = outputValues->satRateMekf[1]; + satRate[2] = outputValues->satRateMekf[2]; + VectorOperations::subtract(satRate, refSatRate, deltaRate, 3); + // valid checks ? + double quatErrorMtx[4][4] = {{quatRef[3], quatRef[2], -quatRef[1], -quatRef[0]}, + {-quatRef[2], quatRef[3], quatRef[0], -quatRef[1]}, + {quatRef[1], -quatRef[0], quatRef[3], -quatRef[2]}, + {quatRef[0], -quatRef[1], quatRef[2], quatRef[3]}}; - double quatRef[4] = {0, 0, 0, 0}; - quatRef[0] = acsParameters.targetModeControllerParameters.quatRef[0]; - quatRef[1] = acsParameters.targetModeControllerParameters.quatRef[1]; - quatRef[2] = acsParameters.targetModeControllerParameters.quatRef[2]; - quatRef[3] = acsParameters.targetModeControllerParameters.quatRef[3]; + double quatErrorComplete[4] = {0, 0, 0, 0}; + MatrixOperations::multiply(*quatErrorMtx, targetQuat, quatErrorComplete, 4, 4, 1); - double satRate[3] = {0, 0, 0}; - satRate[0] = outputValues->satRateMekf[0]; - satRate[1] = outputValues->satRateMekf[1]; - satRate[2] = outputValues->satRateMekf[2]; - VectorOperations::subtract(satRate, refSatRate, deltaRate, 3); - // valid checks ? - double quatErrorMtx[4][4] = {{ quatRef[3], quatRef[2], -quatRef[1], -quatRef[0] }, - { -quatRef[2], quatRef[3], quatRef[0], -quatRef[1] }, - { quatRef[1], -quatRef[0], quatRef[3], -quatRef[2] }, - { quatRef[0], -quatRef[1], quatRef[2], quatRef[3] }}; + if (quatErrorComplete[3] < 0) { + quatErrorComplete[3] *= -1; + } - double quatErrorComplete[4] = {0, 0, 0, 0}; - MatrixOperations::multiply(*quatErrorMtx, targetQuat, quatErrorComplete, 4, 4, 1); - - if (quatErrorComplete[3] < 0) { - quatErrorComplete[3] *= -1; - } - - quatError[0] = quatErrorComplete[0]; - quatError[1] = quatErrorComplete[1]; - quatError[2] = quatErrorComplete[2]; - - // target flag in matlab, importance, does look like it only gives - // feedback if pointing control is under 150 arcsec ?? + quatError[0] = quatErrorComplete[0]; + quatError[1] = quatErrorComplete[1]; + quatError[2] = quatErrorComplete[2]; + // target flag in matlab, importance, does look like it only gives + // feedback if pointing control is under 150 arcsec ?? } +void Guidance::getDistributionMatrixRw(ACS::SensorValues *sensorValues, double *rwPseudoInv) { + if (sensorValues->rw1Set.isValid() && sensorValues->rw2Set.isValid() && sensorValues->rw3Set.isValid() && + sensorValues->rw4Set.isValid()) { + rwPseudoInv[0] = acsParameters.rwMatrices.pseudoInverse[0][0]; + rwPseudoInv[1] = acsParameters.rwMatrices.pseudoInverse[0][1]; + rwPseudoInv[2] = acsParameters.rwMatrices.pseudoInverse[0][2]; + rwPseudoInv[3] = acsParameters.rwMatrices.pseudoInverse[1][0]; + rwPseudoInv[4] = acsParameters.rwMatrices.pseudoInverse[1][1]; + rwPseudoInv[5] = acsParameters.rwMatrices.pseudoInverse[1][2]; + rwPseudoInv[6] = acsParameters.rwMatrices.pseudoInverse[2][0]; + rwPseudoInv[7] = acsParameters.rwMatrices.pseudoInverse[2][1]; + rwPseudoInv[8] = acsParameters.rwMatrices.pseudoInverse[2][2]; + rwPseudoInv[9] = acsParameters.rwMatrices.pseudoInverse[3][0]; + rwPseudoInv[10] = acsParameters.rwMatrices.pseudoInverse[3][1]; + rwPseudoInv[11] = acsParameters.rwMatrices.pseudoInverse[3][2]; -void Guidance::getDistributionMatrixRw(ACS::SensorValues* sensorValues, double *rwPseudoInv) { + } - if (sensorValues->validRw0 && sensorValues->validRw1 && sensorValues->validRw2 && sensorValues->validRw3) { + else if (!(sensorValues->rw1Set.isValid()) && sensorValues->rw2Set.isValid() && + sensorValues->rw3Set.isValid() && sensorValues->rw4Set.isValid()) { + rwPseudoInv[0] = acsParameters.rwMatrices.without0[0][0]; + rwPseudoInv[1] = acsParameters.rwMatrices.without0[0][1]; + rwPseudoInv[2] = acsParameters.rwMatrices.without0[0][2]; + rwPseudoInv[3] = acsParameters.rwMatrices.without0[1][0]; + rwPseudoInv[4] = acsParameters.rwMatrices.without0[1][1]; + rwPseudoInv[5] = acsParameters.rwMatrices.without0[1][2]; + rwPseudoInv[6] = acsParameters.rwMatrices.without0[2][0]; + rwPseudoInv[7] = acsParameters.rwMatrices.without0[2][1]; + rwPseudoInv[8] = acsParameters.rwMatrices.without0[2][2]; + rwPseudoInv[9] = acsParameters.rwMatrices.without0[3][0]; + rwPseudoInv[10] = acsParameters.rwMatrices.without0[3][1]; + rwPseudoInv[11] = acsParameters.rwMatrices.without0[3][2]; + } - rwPseudoInv[0] = acsParameters.rwMatrices.pseudoInverse[0][0]; - rwPseudoInv[1] = acsParameters.rwMatrices.pseudoInverse[0][1]; - rwPseudoInv[2] = acsParameters.rwMatrices.pseudoInverse[0][2]; - rwPseudoInv[3] = acsParameters.rwMatrices.pseudoInverse[1][0]; - rwPseudoInv[4] = acsParameters.rwMatrices.pseudoInverse[1][1]; - rwPseudoInv[5] = acsParameters.rwMatrices.pseudoInverse[1][2]; - rwPseudoInv[6] = acsParameters.rwMatrices.pseudoInverse[2][0]; - rwPseudoInv[7] = acsParameters.rwMatrices.pseudoInverse[2][1]; - rwPseudoInv[8] = acsParameters.rwMatrices.pseudoInverse[2][2]; - rwPseudoInv[9] = acsParameters.rwMatrices.pseudoInverse[3][0]; - rwPseudoInv[10] = acsParameters.rwMatrices.pseudoInverse[3][1]; - rwPseudoInv[11] = acsParameters.rwMatrices.pseudoInverse[3][2]; + else if ((sensorValues->rw1Set.isValid()) && !(sensorValues->rw2Set.isValid()) && + sensorValues->rw3Set.isValid() && sensorValues->rw4Set.isValid()) { + rwPseudoInv[0] = acsParameters.rwMatrices.without1[0][0]; + rwPseudoInv[1] = acsParameters.rwMatrices.without1[0][1]; + rwPseudoInv[2] = acsParameters.rwMatrices.without1[0][2]; + rwPseudoInv[3] = acsParameters.rwMatrices.without1[1][0]; + rwPseudoInv[4] = acsParameters.rwMatrices.without1[1][1]; + rwPseudoInv[5] = acsParameters.rwMatrices.without1[1][2]; + rwPseudoInv[6] = acsParameters.rwMatrices.without1[2][0]; + rwPseudoInv[7] = acsParameters.rwMatrices.without1[2][1]; + rwPseudoInv[8] = acsParameters.rwMatrices.without1[2][2]; + rwPseudoInv[9] = acsParameters.rwMatrices.without1[3][0]; + rwPseudoInv[10] = acsParameters.rwMatrices.without1[3][1]; + rwPseudoInv[11] = acsParameters.rwMatrices.without1[3][2]; + } - } + else if ((sensorValues->rw1Set.isValid()) && (sensorValues->rw2Set.isValid()) && + !(sensorValues->rw3Set.isValid()) && sensorValues->rw4Set.isValid()) { + rwPseudoInv[0] = acsParameters.rwMatrices.without2[0][0]; + rwPseudoInv[1] = acsParameters.rwMatrices.without2[0][1]; + rwPseudoInv[2] = acsParameters.rwMatrices.without2[0][2]; + rwPseudoInv[3] = acsParameters.rwMatrices.without2[1][0]; + rwPseudoInv[4] = acsParameters.rwMatrices.without2[1][1]; + rwPseudoInv[5] = acsParameters.rwMatrices.without2[1][2]; + rwPseudoInv[6] = acsParameters.rwMatrices.without2[2][0]; + rwPseudoInv[7] = acsParameters.rwMatrices.without2[2][1]; + rwPseudoInv[8] = acsParameters.rwMatrices.without2[2][2]; + rwPseudoInv[9] = acsParameters.rwMatrices.without2[3][0]; + rwPseudoInv[10] = acsParameters.rwMatrices.without2[3][1]; + rwPseudoInv[11] = acsParameters.rwMatrices.without2[3][2]; + } - else if (!(sensorValues->validRw0) && sensorValues->validRw1 && sensorValues->validRw2 && sensorValues->validRw3) { + else if ((sensorValues->rw1Set.isValid()) && (sensorValues->rw2Set.isValid()) && + (sensorValues->rw3Set.isValid()) && !(sensorValues->rw4Set.isValid())) { + rwPseudoInv[0] = acsParameters.rwMatrices.without3[0][0]; + rwPseudoInv[1] = acsParameters.rwMatrices.without3[0][1]; + rwPseudoInv[2] = acsParameters.rwMatrices.without3[0][2]; + rwPseudoInv[3] = acsParameters.rwMatrices.without3[1][0]; + rwPseudoInv[4] = acsParameters.rwMatrices.without3[1][1]; + rwPseudoInv[5] = acsParameters.rwMatrices.without3[1][2]; + rwPseudoInv[6] = acsParameters.rwMatrices.without3[2][0]; + rwPseudoInv[7] = acsParameters.rwMatrices.without3[2][1]; + rwPseudoInv[8] = acsParameters.rwMatrices.without3[2][2]; + rwPseudoInv[9] = acsParameters.rwMatrices.without3[3][0]; + rwPseudoInv[10] = acsParameters.rwMatrices.without3[3][1]; + rwPseudoInv[11] = acsParameters.rwMatrices.without3[3][2]; + } - rwPseudoInv[0] = acsParameters.rwMatrices.without0[0][0]; - rwPseudoInv[1] = acsParameters.rwMatrices.without0[0][1]; - rwPseudoInv[2] = acsParameters.rwMatrices.without0[0][2]; - rwPseudoInv[3] = acsParameters.rwMatrices.without0[1][0]; - rwPseudoInv[4] = acsParameters.rwMatrices.without0[1][1]; - rwPseudoInv[5] = acsParameters.rwMatrices.without0[1][2]; - rwPseudoInv[6] = acsParameters.rwMatrices.without0[2][0]; - rwPseudoInv[7] = acsParameters.rwMatrices.without0[2][1]; - rwPseudoInv[8] = acsParameters.rwMatrices.without0[2][2]; - rwPseudoInv[9] = acsParameters.rwMatrices.without0[3][0]; - rwPseudoInv[10] = acsParameters.rwMatrices.without0[3][1]; - rwPseudoInv[11] = acsParameters.rwMatrices.without0[3][2]; - } - - else if ((sensorValues->validRw0) && !(sensorValues->validRw1) && sensorValues->validRw2 && sensorValues->validRw3) { - - rwPseudoInv[0] = acsParameters.rwMatrices.without1[0][0]; - rwPseudoInv[1] = acsParameters.rwMatrices.without1[0][1]; - rwPseudoInv[2] = acsParameters.rwMatrices.without1[0][2]; - rwPseudoInv[3] = acsParameters.rwMatrices.without1[1][0]; - rwPseudoInv[4] = acsParameters.rwMatrices.without1[1][1]; - rwPseudoInv[5] = acsParameters.rwMatrices.without1[1][2]; - rwPseudoInv[6] = acsParameters.rwMatrices.without1[2][0]; - rwPseudoInv[7] = acsParameters.rwMatrices.without1[2][1]; - rwPseudoInv[8] = acsParameters.rwMatrices.without1[2][2]; - rwPseudoInv[9] = acsParameters.rwMatrices.without1[3][0]; - rwPseudoInv[10] = acsParameters.rwMatrices.without1[3][1]; - rwPseudoInv[11] = acsParameters.rwMatrices.without1[3][2]; - } - - else if ((sensorValues->validRw0) && (sensorValues->validRw1) && !(sensorValues->validRw2) && sensorValues->validRw3) { - - rwPseudoInv[0] = acsParameters.rwMatrices.without2[0][0]; - rwPseudoInv[1] = acsParameters.rwMatrices.without2[0][1]; - rwPseudoInv[2] = acsParameters.rwMatrices.without2[0][2]; - rwPseudoInv[3] = acsParameters.rwMatrices.without2[1][0]; - rwPseudoInv[4] = acsParameters.rwMatrices.without2[1][1]; - rwPseudoInv[5] = acsParameters.rwMatrices.without2[1][2]; - rwPseudoInv[6] = acsParameters.rwMatrices.without2[2][0]; - rwPseudoInv[7] = acsParameters.rwMatrices.without2[2][1]; - rwPseudoInv[8] = acsParameters.rwMatrices.without2[2][2]; - rwPseudoInv[9] = acsParameters.rwMatrices.without2[3][0]; - rwPseudoInv[10] = acsParameters.rwMatrices.without2[3][1]; - rwPseudoInv[11] = acsParameters.rwMatrices.without2[3][2]; - } - - else if ((sensorValues->validRw0) && (sensorValues->validRw1) && (sensorValues->validRw2) && !(sensorValues->validRw3)) { - - rwPseudoInv[0] = acsParameters.rwMatrices.without3[0][0]; - rwPseudoInv[1] = acsParameters.rwMatrices.without3[0][1]; - rwPseudoInv[2] = acsParameters.rwMatrices.without3[0][2]; - rwPseudoInv[3] = acsParameters.rwMatrices.without3[1][0]; - rwPseudoInv[4] = acsParameters.rwMatrices.without3[1][1]; - rwPseudoInv[5] = acsParameters.rwMatrices.without3[1][2]; - rwPseudoInv[6] = acsParameters.rwMatrices.without3[2][0]; - rwPseudoInv[7] = acsParameters.rwMatrices.without3[2][1]; - rwPseudoInv[8] = acsParameters.rwMatrices.without3[2][2]; - rwPseudoInv[9] = acsParameters.rwMatrices.without3[3][0]; - rwPseudoInv[10] = acsParameters.rwMatrices.without3[3][1]; - rwPseudoInv[11] = acsParameters.rwMatrices.without3[3][2]; - } - - else { -// @note: This one takes the normal pseudoInverse of all four raction wheels valid. -// Does not make sense, but is implemented that way in MATLAB ?! -// Thought: It does not really play a role, because in case there are more then one -// reaction wheel the pointing control is destined to fail. - rwPseudoInv[0] = acsParameters.rwMatrices.pseudoInverse[0][0]; - rwPseudoInv[1] = acsParameters.rwMatrices.pseudoInverse[0][1]; - rwPseudoInv[2] = acsParameters.rwMatrices.pseudoInverse[0][2]; - rwPseudoInv[3] = acsParameters.rwMatrices.pseudoInverse[1][0]; - rwPseudoInv[4] = acsParameters.rwMatrices.pseudoInverse[1][1]; - rwPseudoInv[5] = acsParameters.rwMatrices.pseudoInverse[1][2]; - rwPseudoInv[6] = acsParameters.rwMatrices.pseudoInverse[2][0]; - rwPseudoInv[7] = acsParameters.rwMatrices.pseudoInverse[2][1]; - rwPseudoInv[8] = acsParameters.rwMatrices.pseudoInverse[2][2]; - rwPseudoInv[9] = acsParameters.rwMatrices.pseudoInverse[3][0]; - rwPseudoInv[10] = acsParameters.rwMatrices.pseudoInverse[3][1]; - rwPseudoInv[11] = acsParameters.rwMatrices.pseudoInverse[3][2]; - - } + else { + // @note: This one takes the normal pseudoInverse of all four raction wheels valid. + // Does not make sense, but is implemented that way in MATLAB ?! + // Thought: It does not really play a role, because in case there are more then one + // reaction wheel the pointing control is destined to fail. + rwPseudoInv[0] = acsParameters.rwMatrices.pseudoInverse[0][0]; + rwPseudoInv[1] = acsParameters.rwMatrices.pseudoInverse[0][1]; + rwPseudoInv[2] = acsParameters.rwMatrices.pseudoInverse[0][2]; + rwPseudoInv[3] = acsParameters.rwMatrices.pseudoInverse[1][0]; + rwPseudoInv[4] = acsParameters.rwMatrices.pseudoInverse[1][1]; + rwPseudoInv[5] = acsParameters.rwMatrices.pseudoInverse[1][2]; + rwPseudoInv[6] = acsParameters.rwMatrices.pseudoInverse[2][0]; + rwPseudoInv[7] = acsParameters.rwMatrices.pseudoInverse[2][1]; + rwPseudoInv[8] = acsParameters.rwMatrices.pseudoInverse[2][2]; + rwPseudoInv[9] = acsParameters.rwMatrices.pseudoInverse[3][0]; + rwPseudoInv[10] = acsParameters.rwMatrices.pseudoInverse[3][1]; + rwPseudoInv[11] = acsParameters.rwMatrices.pseudoInverse[3][2]; + } } diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index bf9894e2..93b9eb47 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -460,8 +460,8 @@ void SensorProcessing::process(timeval now, ACS::SensorValues *sensorValues, sensorValues->mgm3Rm3100Set.fieldStrengths.value, sensorValues->mgm3Rm3100Set.fieldStrengths.isValid(), sensorValues->imtqMgmSet.mtmRawNt.value, sensorValues->imtqMgmSet.mtmRawNt.isValid(), now, &acsParameters->mgmHandlingParameters, - outputValues->gcLatitude, outputValues->gdLongitude, sensorValues->gps0altitude, - sensorValues->gps0Valid, outputValues->magFieldEst, &outputValues->magFieldEstValid, + outputValues->gcLatitude, outputValues->gdLongitude, sensorValues->gpsSet.altitude.value, + sensorValues->gpsSet.isValid(), outputValues->magFieldEst, &outputValues->magFieldEstValid, outputValues->magFieldModel, &outputValues->magFieldModelValid, outputValues->magneticFieldVectorDerivative, &outputValues->magneticFieldVectorDerivativeValid); // VALID outputs- PoolVariable ? diff --git a/mission/controller/acs/SensorValues.cpp b/mission/controller/acs/SensorValues.cpp index b38a35b1..1492ad6e 100644 --- a/mission/controller/acs/SensorValues.cpp +++ b/mission/controller/acs/SensorValues.cpp @@ -60,6 +60,23 @@ ReturnValue_t SensorValues::updateStr() { return result; } +ReturnValue_t SensorValues::updateGps() { + ReturnValue_t result; + PoolReadGuard pgGps(&gpsSet); + + result = pgGps.getReadResult(); + return result; +} + +ReturnValue_t SensorValues::updateRw() { + ReturnValue_t result; + PoolReadGuard pgRw1(&rw1Set), pgRw2(&rw2Set), pgRw3(&rw3Set), pgRw4(&rw4Set); + + result = (pgRw1.getReadResult() || pgRw2.getReadResult() || pgRw3.getReadResult() || + pgRw4.getReadResult()); + return result; +} + ReturnValue_t SensorValues::update() { ReturnValue_t mgmUpdate = updateMgm(); ReturnValue_t susUpdate = updateSus(); diff --git a/mission/controller/acs/SensorValues.h b/mission/controller/acs/SensorValues.h index 4e3a215f..08fe5177 100644 --- a/mission/controller/acs/SensorValues.h +++ b/mission/controller/acs/SensorValues.h @@ -6,9 +6,11 @@ #include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" #include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" #include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" +#include "mission/devices/devicedefinitions/GPSDefinitions.h" #include "mission/devices/devicedefinitions/GyroADIS1650XDefinitions.h" #include "mission/devices/devicedefinitions/GyroL3GD20Definitions.h" #include "mission/devices/devicedefinitions/IMTQHandlerDefinitions.h" +#include "mission/devices/devicedefinitions/RwDefinitions.h" #include "mission/devices/devicedefinitions/SusDefinitions.h" namespace ACS { @@ -22,7 +24,9 @@ class SensorValues { ReturnValue_t updateMgm(); ReturnValue_t updateSus(); ReturnValue_t updateGyr(); + ReturnValue_t updateGps(); ReturnValue_t updateStr(); + ReturnValue_t updateRw(); MGMLIS3MDL::MgmPrimaryDataset mgm0Lis3Set = MGMLIS3MDL::MgmPrimaryDataset(objects::MGM_0_LIS3_HANDLER); @@ -56,33 +60,27 @@ class SensorValues { startracker::SolutionSet strSet = startracker::SolutionSet(objects::STAR_TRACKER); - // double quatJB[4]; // output star tracker. quaternion or dcm ? refrence to which KOS? - // bool quatJBValid; - // int strIntTime[2]; + GpsPrimaryDataset gpsSet = GpsPrimaryDataset(objects::GPS_CONTROLLER); - double gps0latitude; // Reference is WGS84, so this one will probably be geodetic - double gps0longitude; // Should be geocentric for IGRF - double gps0altitude; - double gps0Velocity[3]; // speed over ground = ?? - double gps0Time; // utc + // double gps0latitude; // Reference is WGS84, so this one will probably be geodetic + // double gps0longitude; // Should be geocentric for IGRF + // double gps0altitude; + // double gps0Velocity[3]; // speed over ground = ?? + // double gps0Time; // utc + // + // // valid ids for gps values ! + // int gps0TimeYear; + // int gps0TimeMonth; + // int gps0TimeHour; // should be double + // bool gps0Valid; - // valid ids for gps values ! - int gps0TimeYear; - int gps0TimeMonth; - int gps0TimeHour; // should be double - bool gps0Valid; + // bool mgt0valid; - bool mgt0valid; - // Reaction wheel measurements - double speedRw0; // RPM [1/min] - double speedRw1; // RPM [1/min] - double speedRw2; // RPM [1/min] - double speedRw3; // RPM [1/min] - bool validRw0; - bool validRw1; - bool validRw2; - bool validRw3; + RwDefinitions::StatusSet rw1Set = RwDefinitions::StatusSet(objects::RW1); + RwDefinitions::StatusSet rw2Set = RwDefinitions::StatusSet(objects::RW2); + RwDefinitions::StatusSet rw3Set = RwDefinitions::StatusSet(objects::RW3); + RwDefinitions::StatusSet rw4Set = RwDefinitions::StatusSet(objects::RW4); }; } /* namespace ACS */ diff --git a/mission/controller/acs/control/PtgCtrl.cpp b/mission/controller/acs/control/PtgCtrl.cpp index 999df912..6201a32a 100644 --- a/mission/controller/acs/control/PtgCtrl.cpp +++ b/mission/controller/acs/control/PtgCtrl.cpp @@ -112,54 +112,54 @@ void PtgCtrl::ptgGroundstation(const double mode, const double *qError, const do } -void PtgCtrl::ptgDesaturation(double *magFieldEst, bool *magFieldEstValid, double *satRate, double *speedRw0, - double *speedRw1, double *speedRw2, double *speedRw3, double *mgtDpDes) { - if ( !(magFieldEstValid) || !(pointingModeControllerParameters->desatOn)) { - - mgtDpDes[0] = 0; - mgtDpDes[1] = 0; - mgtDpDes[2] = 0; - return; - - } - -// calculating momentum of satellite and momentum of reaction wheels - double speedRws[4] = {*speedRw0, *speedRw1, *speedRw2, *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); - double momentumSat[3] = {0, 0, 0}, momentumTotal[3] = {0, 0, 0}; - MatrixOperations::multiply(*(inertiaEIVE->inertiaMatrix), satRate, momentumSat, 3, 3, 1); - VectorOperations::add(momentumSat, momentumRw, momentumTotal, 3); -// calculating momentum error - double deltaMomentum[3] = {0, 0, 0}; - VectorOperations::subtract(momentumTotal, pointingModeControllerParameters->desatMomentumRef, deltaMomentum, 3); -// resulting magnetic dipole command - double crossMomentumMagField[3] = {0, 0, 0}; - VectorOperations::cross(deltaMomentum, magFieldEst, crossMomentumMagField); - double normMag = VectorOperations::norm(magFieldEst, 3), factor = 0; - factor = (pointingModeControllerParameters->deSatGainFactor) / normMag; - VectorOperations::mulScalar(crossMomentumMagField, factor, mgtDpDes, 3); +void PtgCtrl::ptgDesaturation(double *magFieldEst, bool *magFieldEstValid, double *satRate, + int32_t *speedRw0, int32_t *speedRw1, int32_t *speedRw2, + int32_t *speedRw3, double *mgtDpDes) { + if (!(magFieldEstValid) || !(pointingModeControllerParameters->desatOn)) { + mgtDpDes[0] = 0; + mgtDpDes[1] = 0; + mgtDpDes[2] = 0; + return; + } + // calculating momentum of satellite and momentum of reaction wheels + double speedRws[4] = {*speedRw0, *speedRw1, *speedRw2, *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); + double momentumSat[3] = {0, 0, 0}, momentumTotal[3] = {0, 0, 0}; + MatrixOperations::multiply(*(inertiaEIVE->inertiaMatrix), satRate, momentumSat, 3, 3, 1); + VectorOperations::add(momentumSat, momentumRw, momentumTotal, 3); + // calculating momentum error + double deltaMomentum[3] = {0, 0, 0}; + VectorOperations::subtract( + momentumTotal, pointingModeControllerParameters->desatMomentumRef, deltaMomentum, 3); + // resulting magnetic dipole command + double crossMomentumMagField[3] = {0, 0, 0}; + VectorOperations::cross(deltaMomentum, magFieldEst, crossMomentumMagField); + double normMag = VectorOperations::norm(magFieldEst, 3), factor = 0; + factor = (pointingModeControllerParameters->deSatGainFactor) / normMag; + VectorOperations::mulScalar(crossMomentumMagField, factor, mgtDpDes, 3); } -void PtgCtrl::ptgNullspace(const double *speedRw0, const double *speedRw1, const double *speedRw2, const double *speedRw3, double *rwTrqNs) { - - double speedRws[4] = {*speedRw0, *speedRw1, *speedRw2, *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 - VectorOperations::mulScalar(rpmOffset, factor, rpmOffset, 4); - 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, wheelMomentum, 4); - double gainNs = pointingModeControllerParameters->gainNullspace; - double nullSpaceMatrix[4][4] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - MathOperations::vecTransposeVecMatrix(rwMatrices->nullspace, rwMatrices->nullspace, *nullSpaceMatrix, 4); - MatrixOperations::multiply(*nullSpaceMatrix, wheelMomentum, rwTrqNs, 4, 4, 1); - VectorOperations::mulScalar(rwTrqNs, gainNs, rwTrqNs, 4); - VectorOperations::mulScalar(rwTrqNs, -1, rwTrqNs, 4); - - +void PtgCtrl::ptgNullspace(const int32_t *speedRw0, const int32_t *speedRw1, + const int32_t *speedRw2, const int32_t *speedRw3, double *rwTrqNs) { + double speedRws[4] = {*speedRw0, *speedRw1, *speedRw2, *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 + VectorOperations::mulScalar(rpmOffset, factor, rpmOffset, 4); + 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, + wheelMomentum, 4); + double gainNs = pointingModeControllerParameters->gainNullspace; + double nullSpaceMatrix[4][4] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MathOperations::vecTransposeVecMatrix(rwMatrices->nullspace, rwMatrices->nullspace, + *nullSpaceMatrix, 4); + MatrixOperations::multiply(*nullSpaceMatrix, wheelMomentum, rwTrqNs, 4, 4, 1); + VectorOperations::mulScalar(rwTrqNs, gainNs, rwTrqNs, 4); + VectorOperations::mulScalar(rwTrqNs, -1, rwTrqNs, 4); } diff --git a/mission/controller/acs/control/PtgCtrl.h b/mission/controller/acs/control/PtgCtrl.h index 87a66f2d..be67187d 100644 --- a/mission/controller/acs/control/PtgCtrl.h +++ b/mission/controller/acs/control/PtgCtrl.h @@ -4,8 +4,8 @@ * 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 + * @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 @@ -14,46 +14,49 @@ #ifndef PTGCTRL_H_ #define PTGCTRL_H_ -#include "../SensorValues.h" -#include "../OutputValues.h" -#include "../AcsParameters.h" -#include "../config/classIds.h" -#include #include +#include #include -class PtgCtrl{ +#include "../AcsParameters.h" +#include "../OutputValues.h" +#include "../SensorValues.h" +#include "../config/classIds.h" -public: - /* @brief: Constructor - * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters - */ - PtgCtrl(AcsParameters *acsParameters_); - virtual ~PtgCtrl(); +class PtgCtrl { + public: + /* @brief: Constructor + * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters + */ + PtgCtrl(AcsParameters *acsParameters_); + virtual ~PtgCtrl(); - static const uint8_t INTERFACE_ID = CLASS_ID::PTG; - static const ReturnValue_t PTGCTRL_MEKF_INPUT_INVALID = MAKE_RETURN_CODE(0x01); + static const uint8_t INTERFACE_ID = CLASS_ID::PTG; + static const ReturnValue_t PTGCTRL_MEKF_INPUT_INVALID = MAKE_RETURN_CODE(0x01); - /* @brief: Load AcsParameters für this class - * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters - */ - void loadAcsParameters(AcsParameters *acsParameters_); + /* @brief: Load AcsParameters für 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 ptgGroundstation(const double mode,const double *qError,const double *deltaRate,const double *rwPseudoInv, double *torqueRws); + /* @brief: Calculates the needed torque for the pointing control mechanism + * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters + */ + void ptgGroundstation(const double mode, const double *qError, const double *deltaRate, + const double *rwPseudoInv, double *torqueRws); - void ptgDesaturation(double *magFieldEst, bool *magFieldEstValid, double *satRate, double *speedRw0, - double *speedRw1, double *speedRw2, double *speedRw3, double *mgtDpDes); + void ptgDesaturation(double *magFieldEst, bool *magFieldEstValid, double *satRate, + int32_t *speedRw0, int32_t *speedRw1, int32_t *speedRw2, int32_t *speedRw3, + double *mgtDpDes); - void ptgNullspace(const double *speedRw0, const double *speedRw1, const double *speedRw2, const double *speedRw3, double *rwTrqNs); + void ptgNullspace(const int32_t *speedRw0, const int32_t *speedRw1, const int32_t *speedRw2, + const int32_t *speedRw3, double *rwTrqNs); -private: - AcsParameters::PointingModeControllerParameters* pointingModeControllerParameters; - AcsParameters::RwHandlingParameters* rwHandlingParameters; - AcsParameters::InertiaEIVE* inertiaEIVE; - AcsParameters::RwMatrices* rwMatrices; + private: + AcsParameters::PointingModeControllerParameters *pointingModeControllerParameters; + AcsParameters::RwHandlingParameters *rwHandlingParameters; + AcsParameters::InertiaEIVE *inertiaEIVE; + AcsParameters::RwMatrices *rwMatrices; }; #endif /* ACS_CONTROL_PTGCTRL_H_ */ -- 2.34.1 From 43497b399faca19363a1a9565611c15e11992998 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 12 Oct 2022 15:18:07 +0200 Subject: [PATCH 059/101] enabled processGps --- mission/controller/acs/SensorProcessing.cpp | 4 ++-- mission/controller/acs/SensorValues.cpp | 1 + 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index 93b9eb47..dc930fc8 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -447,8 +447,8 @@ void SensorProcessing::process(timeval now, ACS::SensorValues *sensorValues, ACS::OutputValues *outputValues, const AcsParameters *acsParameters) { sensorValues->update(); - // processGps(sensorValues->gps0latitude, sensorValues->gps0longitude, sensorValues->gps0Valid, - // &outputValues->gcLatitude, &outputValues->gdLongitude); + processGps(sensorValues->gpsSet.latitude.value, sensorValues->gpsSet.longitude.value, + sensorValues->gpsSet.isValid(), &outputValues->gcLatitude, &outputValues->gdLongitude); outputValues->mgmUpdated = processMgm( sensorValues->mgm0Lis3Set.fieldStrengths.value, diff --git a/mission/controller/acs/SensorValues.cpp b/mission/controller/acs/SensorValues.cpp index 1492ad6e..acc6f3eb 100644 --- a/mission/controller/acs/SensorValues.cpp +++ b/mission/controller/acs/SensorValues.cpp @@ -82,6 +82,7 @@ ReturnValue_t SensorValues::update() { ReturnValue_t susUpdate = updateSus(); ReturnValue_t gyrUpdate = updateGyr(); ReturnValue_t strUpdate = updateStr(); + if ((mgmUpdate && susUpdate && gyrUpdate && strUpdate) == returnvalue::FAILED) { return returnvalue::FAILED; }; -- 2.34.1 From 8edf7fc0de244a627e7515b69c9e0895245d4349 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 12 Oct 2022 15:22:26 +0200 Subject: [PATCH 060/101] deprecated code removed --- mission/controller/acs/SensorValues.h | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/mission/controller/acs/SensorValues.h b/mission/controller/acs/SensorValues.h index 08fe5177..1a260635 100644 --- a/mission/controller/acs/SensorValues.h +++ b/mission/controller/acs/SensorValues.h @@ -62,21 +62,8 @@ class SensorValues { GpsPrimaryDataset gpsSet = GpsPrimaryDataset(objects::GPS_CONTROLLER); - // double gps0latitude; // Reference is WGS84, so this one will probably be geodetic - // double gps0longitude; // Should be geocentric for IGRF - // double gps0altitude; - // double gps0Velocity[3]; // speed over ground = ?? - // double gps0Time; // utc - // - // // valid ids for gps values ! - // int gps0TimeYear; - // int gps0TimeMonth; - // int gps0TimeHour; // should be double - // bool gps0Valid; - // bool mgt0valid; - RwDefinitions::StatusSet rw1Set = RwDefinitions::StatusSet(objects::RW1); RwDefinitions::StatusSet rw2Set = RwDefinitions::StatusSet(objects::RW2); RwDefinitions::StatusSet rw3Set = RwDefinitions::StatusSet(objects::RW3); -- 2.34.1 From cc35db91cdd48e55e1498a4039fada076393f8a2 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 12 Oct 2022 17:14:33 +0200 Subject: [PATCH 061/101] added calibration of raw MGM values --- mission/controller/acs/AcsParameters.h | 19 +++++++++++ mission/controller/acs/SensorProcessing.cpp | 36 +++++++++++++++++---- 2 files changed, 49 insertions(+), 6 deletions(-) diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 29caa59e..6c72d9e5 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -36,6 +36,25 @@ class AcsParameters /*: public HasParametersIF*/ { float mgm2orientationMatrix[3][3] = {{0, 0, -1}, {0, 1, 0}, {1, 0, 0}}; float mgm3orientationMatrix[3][3] = {{0, 0, 1}, {0, -1, 0}, {1, 0, 0}}; float mgm4orientationMatrix[3][3] = {{0, 0, -1}, {-1, 0, 0}, {0, 1, 0}}; + + float mgm0hardIronOffset[3] = {19.89364, -29.94111, -31.07508}; + float mgm1hardIronOffset[3] = {10.95500, -8.053403, -33.36383}; + float mgm2hardIronOffset[3] = {15.72181, -26.87090, -62.19010}; + float mgm3hardIronOffset[3] = {0.0, 0.0, 0.0}; + float mgm4hardIronOffset[3] = {0.0, 0.0, 0.0}; + + float mgm0softIronInverse[3][3] = {{1420.727e-3, 9.352825e-3, -127.1979e-3}, + {9.352825e-3, 1031.965e-3, -80.02734e-3}, + {-127.1979e-3, -80.02734e-3, 934.8899e-3}}; + float mgm1softIronInverse[3][3] = {{126.7325e-2, -4.146410e-2, -18.37963e-2}, + {-4.146410e-2, 109.3310e-2, -5.246314e-2}, + {-18.37963e-2, -5.246314e-2, 105.7300e-2}}; + float mgm2softIronInverse[3][3] = {{143.0438e-2, 7.095763e-2, 15.67482e-2}, + {7.095763e-2, 99.65167e-2, -6.958760e-2}, + {15.67482e-2, -6.958760e-2, 94.50124e-2}}; + float mgm3softIronInverse[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}}; + float mgm4softIronInverse[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}}; + } mgmHandlingParameters; struct SusHandlingParameters { diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index dc930fc8..998927f6 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -42,38 +42,62 @@ bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const validMagField = false; return false; } - // Transforming Values to the Body Frame (actually it is the geometry frame atm) + float mgm0ValueNoBias[3] = {0, 0, 0}, mgm1ValueNoBias[3] = {0, 0, 0}, + mgm2ValueNoBias[3] = {0, 0, 0}, mgm3ValueNoBias[3] = {0, 0, 0}, + mgm4ValueNoBias[3] = {0, 0, 0}; + float mgm0ValueCalib[3] = {0, 0, 0}, mgm1ValueCalib[3] = {0, 0, 0}, mgm2ValueCalib[3] = {0, 0, 0}, + mgm3ValueCalib[3] = {0, 0, 0}, mgm4ValueCalib[3] = {0, 0, 0}; float mgm0ValueBody[3] = {0, 0, 0}, mgm1ValueBody[3] = {0, 0, 0}, mgm2ValueBody[3] = {0, 0, 0}, mgm3ValueBody[3] = {0, 0, 0}, mgm4ValueBody[3] = {0, 0, 0}; bool validUnit[5] = {false, false, false, false, false}; uint8_t validCount = 0; if (mgm0valid) { - MatrixOperations::multiply(mgmParameters->mgm0orientationMatrix[0], mgm0Value, + VectorOperations::subtract(mgm0Value, mgmParameters->mgm0hardIronOffset, mgm0ValueNoBias, + 3); + MatrixOperations::multiply(mgmParameters->mgm0softIronInverse[0], mgm0ValueNoBias, + mgm0ValueCalib, 3, 3, 1); + MatrixOperations::multiply(mgmParameters->mgm0orientationMatrix[0], mgm0ValueCalib, mgm0ValueBody, 3, 3, 1); validCount += 1; validUnit[0] = true; } if (mgm1valid) { - MatrixOperations::multiply(mgmParameters->mgm1orientationMatrix[0], mgm1Value, + VectorOperations::subtract(mgm1Value, mgmParameters->mgm1hardIronOffset, mgm1ValueNoBias, + 3); + MatrixOperations::multiply(mgmParameters->mgm1softIronInverse[0], mgm1ValueNoBias, + mgm1ValueCalib, 3, 3, 1); + MatrixOperations::multiply(mgmParameters->mgm1orientationMatrix[0], mgm1ValueCalib, mgm1ValueBody, 3, 3, 1); validCount += 1; validUnit[1] = true; } if (mgm2valid) { - MatrixOperations::multiply(mgmParameters->mgm2orientationMatrix[0], mgm2Value, + VectorOperations::subtract(mgm2Value, mgmParameters->mgm2hardIronOffset, mgm2ValueNoBias, + 3); + MatrixOperations::multiply(mgmParameters->mgm2softIronInverse[0], mgm2ValueNoBias, + mgm2ValueCalib, 3, 3, 1); + MatrixOperations::multiply(mgmParameters->mgm2orientationMatrix[0], mgm2ValueCalib, mgm2ValueBody, 3, 3, 1); validCount += 1; validUnit[2] = true; } if (mgm3valid) { - MatrixOperations::multiply(mgmParameters->mgm3orientationMatrix[0], mgm3Value, + VectorOperations::subtract(mgm3Value, mgmParameters->mgm3hardIronOffset, mgm3ValueNoBias, + 3); + MatrixOperations::multiply(mgmParameters->mgm3softIronInverse[0], mgm3ValueNoBias, + mgm3ValueCalib, 3, 3, 1); + MatrixOperations::multiply(mgmParameters->mgm3orientationMatrix[0], mgm3ValueCalib, mgm3ValueBody, 3, 3, 1); validCount += 1; validUnit[3] = true; } if (mgm4valid) { - MatrixOperations::multiply(mgmParameters->mgm4orientationMatrix[0], mgm4Value, + VectorOperations::subtract(mgm4Value, mgmParameters->mgm4hardIronOffset, mgm4ValueNoBias, + 3); + MatrixOperations::multiply(mgmParameters->mgm4softIronInverse[0], mgm4ValueNoBias, + mgm4ValueCalib, 3, 3, 1); + MatrixOperations::multiply(mgmParameters->mgm4orientationMatrix[0], mgm4ValueCalib, mgm4ValueBody, 3, 3, 1); validCount += 1; validUnit[4] = true; -- 2.34.1 From f89f7630c179aff7d33ace5406ca49f1009b4eea Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 13 Oct 2022 10:49:39 +0200 Subject: [PATCH 062/101] removed comment --- mission/controller/acs/SensorValues.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mission/controller/acs/SensorValues.cpp b/mission/controller/acs/SensorValues.cpp index acc6f3eb..152f866c 100644 --- a/mission/controller/acs/SensorValues.cpp +++ b/mission/controller/acs/SensorValues.cpp @@ -90,4 +90,4 @@ ReturnValue_t SensorValues::update() { } } // namespace ACS -// namespace ACS + -- 2.34.1 From 8f61d14a828fb897f0db06d21861b06978438d9b Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Fri, 14 Oct 2022 11:11:23 +0200 Subject: [PATCH 063/101] implemented getParameter for AcsParameters --- mission/controller/acs/AcsParameters.cpp | 536 ++++++++++++++++++++++- 1 file changed, 530 insertions(+), 6 deletions(-) diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index 0b516c13..ca1057bc 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -3,15 +3,539 @@ #include #include -#include - -AcsParameters::AcsParameters() {} +AcsParameters::AcsParameters(){}; //(uint8_t parameterModuleId) : + // parameterModuleId(parameterModuleId) {} AcsParameters::~AcsParameters() {} -/* -ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint16_t parameterId, + +/*ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint16_t parameterId, ParameterWrapper* parameterWrapper, const ParameterWrapper* newValues, uint16_t startAtIndex) { - return returnvalue::OK; + if (domainId == parameterModuleId) { + switch (parameterId >> 8) { + case 0x0: // direct members + switch (parameterId & 0xFF) { + default: + return INVALID_IDENTIFIER_ID; + } + break; + case 0x1: // OnBoardParams + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(onBoardParams.sampleTime); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case 0x2: // InertiaEIVE + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(inertiaEIVE.inertiaMatrix); + break; + case 0x1: + parameterWrapper->set(inertiaEIVE.inertiaMatrixInverse); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case 0x3: // MgmHandlingParameters + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(mgmHandlingParameters.mgm0orientationMatrix); + break; + case 0x1: + parameterWrapper->set(mgmHandlingParameters.mgm1orientationMatrix); + break; + case 0x2: + parameterWrapper->set(mgmHandlingParameters.mgm2orientationMatrix); + break; + case 0x3: + parameterWrapper->set(mgmHandlingParameters.mgm3orientationMatrix); + break; + case 0x4: + parameterWrapper->set(mgmHandlingParameters.mgm4orientationMatrix); + break; + case 0x5: + parameterWrapper->set(mgmHandlingParameters.mgm0hardIronOffset); + break; + case 0x6: + parameterWrapper->set(mgmHandlingParameters.mgm1hardIronOffset); + break; + case 0x7: + parameterWrapper->set(mgmHandlingParameters.mgm2hardIronOffset); + break; + case 0x8: + parameterWrapper->set(mgmHandlingParameters.mgm3hardIronOffset); + break; + case 0x9: + parameterWrapper->set(mgmHandlingParameters.mgm4hardIronOffset); + break; + case 0xA: + parameterWrapper->set(mgmHandlingParameters.mgm0softIronInverse); + break; + case 0xB: + parameterWrapper->set(mgmHandlingParameters.mgm1softIronInverse); + break; + case 0xC: + parameterWrapper->set(mgmHandlingParameters.mgm2softIronInverse); + break; + case 0xD: + parameterWrapper->set(mgmHandlingParameters.mgm3softIronInverse); + break; + case 0xE: + parameterWrapper->set(mgmHandlingParameters.mgm4softIronInverse); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case 0x4: // SusHandlingParameters + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(susHandlingParameters.sus0orientationMatrix); + break; + case 0x1: + parameterWrapper->set(susHandlingParameters.sus1orientationMatrix); + break; + case 0x2: + parameterWrapper->set(susHandlingParameters.sus2orientationMatrix); + break; + case 0x3: + parameterWrapper->set(susHandlingParameters.sus3orientationMatrix); + break; + case 0x4: + parameterWrapper->set(susHandlingParameters.sus4orientationMatrix); + break; + case 0x5: + parameterWrapper->set(susHandlingParameters.sus5orientationMatrix); + break; + case 0x6: + parameterWrapper->set(susHandlingParameters.sus6orientationMatrix); + break; + case 0x7: + parameterWrapper->set(susHandlingParameters.sus7orientationMatrix); + break; + case 0x8: + parameterWrapper->set(susHandlingParameters.sus8orientationMatrix); + break; + case 0x9: + parameterWrapper->set(susHandlingParameters.sus9orientationMatrix); + break; + case 0xA: + parameterWrapper->set(susHandlingParameters.sus10orientationMatrix); + break; + case 0xB: + parameterWrapper->set(susHandlingParameters.sus11orientationMatrix); + break; + case 0xC: + parameterWrapper->set(susHandlingParameters.sus0coeffAlpha); + break; + case 0xD: + parameterWrapper->set(susHandlingParameters.sus0coeffBeta); + break; + case 0xE: + parameterWrapper->set(susHandlingParameters.sus1coeffAlpha); + break; + case 0xF: + parameterWrapper->set(susHandlingParameters.sus1coeffBeta); + break; + case 0x10: + parameterWrapper->set(susHandlingParameters.sus2coeffAlpha); + break; + case 0x11: + parameterWrapper->set(susHandlingParameters.sus2coeffBeta); + break; + case 0x12: + parameterWrapper->set(susHandlingParameters.sus3coeffAlpha); + break; + case 0x13: + parameterWrapper->set(susHandlingParameters.sus3coeffBeta); + break; + case 0x14: + parameterWrapper->set(susHandlingParameters.sus4coeffAlpha); + break; + case 0x15: + parameterWrapper->set(susHandlingParameters.sus4coeffBeta); + break; + case 0x16: + parameterWrapper->set(susHandlingParameters.sus5coeffAlpha); + break; + case 0x17: + parameterWrapper->set(susHandlingParameters.sus5coeffBeta); + break; + case 0x18: + parameterWrapper->set(susHandlingParameters.sus6coeffAlpha); + break; + case 0x19: + parameterWrapper->set(susHandlingParameters.sus6coeffBeta); + break; + case 0x1A: + parameterWrapper->set(susHandlingParameters.sus7coeffAlpha); + break; + case 0x1B: + parameterWrapper->set(susHandlingParameters.sus7coeffBeta); + break; + case 0x1C: + parameterWrapper->set(susHandlingParameters.sus8coeffAlpha); + break; + case 0x1D: + parameterWrapper->set(susHandlingParameters.sus8coeffBeta); + break; + case 0x1E: + parameterWrapper->set(susHandlingParameters.sus9coeffAlpha); + break; + case 0x1F: + parameterWrapper->set(susHandlingParameters.sus9coeffBeta); + break; + case 0x20: + parameterWrapper->set(susHandlingParameters.sus10coeffAlpha); + break; + case 0x21: + parameterWrapper->set(susHandlingParameters.sus10coeffBeta); + break; + case 0x22: + parameterWrapper->set(susHandlingParameters.sus11coeffAlpha); + break; + case 0x23: + parameterWrapper->set(susHandlingParameters.sus11coeffBeta); + break; + case 0x24: + parameterWrapper->set(susHandlingParameters.filterAlpha); + break; + case 0x25: + parameterWrapper->set(susHandlingParameters.sunThresh); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0x5): // GyrHandlingParameters + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(gyrHandlingParameters.gyr0orientationMatrix); + break; + case 0x1: + parameterWrapper->set(gyrHandlingParameters.gyr1orientationMatrix); + break; + case 0x2: + parameterWrapper->set(gyrHandlingParameters.gyr2orientationMatrix); + break; + case 0x3: + parameterWrapper->set(gyrHandlingParameters.gyr3orientationMatrix); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0x6): // RwHandlingParameters + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(rwHandlingParameters.rw0orientationMatrix); + break; + case 0x1: + parameterWrapper->set(rwHandlingParameters.rw1orientationMatrix); + break; + case 0x2: + parameterWrapper->set(rwHandlingParameters.rw2orientationMatrix); + break; + case 0x3: + parameterWrapper->set(rwHandlingParameters.rw3orientationMatrix); + break; + case 0x4: + parameterWrapper->set(rwHandlingParameters.inertiaWheel); + break; + case 0x5: + parameterWrapper->set(rwHandlingParameters.maxTrq); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0x7): // RwMatrices + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(rwMatrices.alignmentMatrix); + break; + case 0x1: + parameterWrapper->set(rwMatrices.pseudoInverse); + break; + case 0x2: + parameterWrapper->set(rwMatrices.without0); + break; + case 0x3: + parameterWrapper->set(rwMatrices.without1); + break; + case 0x4: + parameterWrapper->set(rwMatrices.without2); + break; + case 0x5: + parameterWrapper->set(rwMatrices.without3); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0x8): // SafeModeControllerParameters + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(safeModeControllerParameters.k_rate_mekf); + break; + case 0x1: + parameterWrapper->set(safeModeControllerParameters.k_align_mekf); + break; + case 0x2: + parameterWrapper->set(safeModeControllerParameters.k_rate_no_mekf); + break; + case 0x3: + parameterWrapper->set(safeModeControllerParameters.k_align_no_mekf); + break; + case 0x4: + parameterWrapper->set(safeModeControllerParameters.sunMagAngleMin); + break; + case 0x5: + parameterWrapper->set(safeModeControllerParameters.sunTargetDir); + break; + case 0x6: + parameterWrapper->set(safeModeControllerParameters.satRateRef); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0x9): // DetumbleCtrlParameters + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(detumbleCtrlParameters.gainD); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0xA): // PointingModeControllerParameters + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(targetModeControllerParameters.updtFlag); + break; + case 0x1: + parameterWrapper->set(targetModeControllerParameters.A_rw); + break; + case 0x2: + parameterWrapper->set(targetModeControllerParameters.refDirection); + break; + case 0x3: + parameterWrapper->set(targetModeControllerParameters.refRotRate); + break; + case 0x4: + parameterWrapper->set(targetModeControllerParameters.quatRef); + break; + case 0x5: + parameterWrapper->set(targetModeControllerParameters.avoidBlindStr); + break; + case 0x6: + parameterWrapper->set(targetModeControllerParameters.blindAvoidStart); + break; + case 0x7: + parameterWrapper->set(targetModeControllerParameters.blindAvoidStop); + break; + case 0x8: + parameterWrapper->set(targetModeControllerParameters.blindRotRate); + break; + case 0x9: + parameterWrapper->set(targetModeControllerParameters.zeta); + break; + case 0xA: + parameterWrapper->set(targetModeControllerParameters.zetaLow); + break; + case 0xB: + parameterWrapper->set(targetModeControllerParameters.om); + break; + case 0xC: + parameterWrapper->set(targetModeControllerParameters.omLow); + break; + case 0xD: + parameterWrapper->set(targetModeControllerParameters.omMax); + break; + case 0xE: + parameterWrapper->set(targetModeControllerParameters.qiMin); + break; + case 0xF: + parameterWrapper->set(targetModeControllerParameters.gainNullspace); + break; + case 0x10: + parameterWrapper->set(targetModeControllerParameters.desatMomentumRef); + break; + case 0x11: + parameterWrapper->set(targetModeControllerParameters.deSatGainFactor); + break; + case 0x12: + parameterWrapper->set(targetModeControllerParameters.desatOn); + break; + case 0x13: + parameterWrapper->set(targetModeControllerParameters.omegaEarth); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0xB): // StrParameters + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(strParameters.exclusionAngle); + break; + case 0x1: + parameterWrapper->set(strParameters.boresightAxis); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0xC): // GpsParameters + switch (parameterId & 0xFF) { + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0xD): // GroundStationParameters + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(groundStationParameters.latitudeGs); + break; + case 0x1: + parameterWrapper->set(groundStationParameters.longitudeGs); + break; + case 0x2: + parameterWrapper->set(groundStationParameters.altitudeGs); + break; + case 0x3: + parameterWrapper->set(groundStationParameters.earthRadiusEquat); + break; + case 0x4: + parameterWrapper->set(groundStationParameters.earthRadiusPolar); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0xE): // SunModelParameters + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(sunModelParameters.useSunModel); + break; + case 0x1: + parameterWrapper->set(sunModelParameters.domega); + break; + case 0x2: + parameterWrapper->set(sunModelParameters.omega_0); + break; + case 0x3: + parameterWrapper->set(sunModelParameters.m_0); + break; + case 0x4: + parameterWrapper->set(sunModelParameters.dm); + break; + case 0x5: + parameterWrapper->set(sunModelParameters.e); + break; + case 0x6: + parameterWrapper->set(sunModelParameters.e1); + break; + case 0x7: + parameterWrapper->set(sunModelParameters.p1); + break; + case 0x8: + parameterWrapper->set(sunModelParameters.p2); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0xF): // KalmanFilterParameters + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(kalmanFilterParameters.activateKalmanFilter); + break; + case 0x1: + parameterWrapper->set(kalmanFilterParameters.requestResetFlag); + break; + case 0x2: + parameterWrapper->set( + kalmanFilterParameters.maxToleratedTimeBetweenKalmanFilterExecutionSteps); + break; + case 0x3: + parameterWrapper->set(kalmanFilterParameters.processNoiseOmega); + break; + case 0x4: + parameterWrapper->set(kalmanFilterParameters.processNoiseQuaternion); + break; + case 0x5: + parameterWrapper->set(kalmanFilterParameters.sensorNoiseSTR); + break; + case 0x6: + parameterWrapper->set(kalmanFilterParameters.sensorNoiseSS); + break; + case 0x7: + parameterWrapper->set(kalmanFilterParameters.sensorNoiseMAG); + break; + case 0x8: + parameterWrapper->set(kalmanFilterParameters.sensorNoiseGYR); + break; + case 0x9: + parameterWrapper->set(kalmanFilterParameters.sensorNoiseArwGYR); + break; + case 0xA: + parameterWrapper->set(kalmanFilterParameters.sensorNoiseBsGYR); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0x10): // MagnetorquesParameter + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(magnetorquesParameter.mtq0orientationMatrix); + break; + case 0x1: + parameterWrapper->set(magnetorquesParameter.mtq1orientationMatrix); + break; + case 0x2: + parameterWrapper->set(magnetorquesParameter.mtq2orientationMatrix); + break; + case 0x3: + parameterWrapper->set(magnetorquesParameter.alignmentMatrixMtq); + break; + case 0x4: + parameterWrapper->set(magnetorquesParameter.inverseAlignment); + break; + case 0x5: + parameterWrapper->set(magnetorquesParameter.DipolMax); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + case (0x11): // DetumbleParameter + switch (parameterId & 0xFF) { + case 0x0: + parameterWrapper->set(detumbleParameter.detumblecounter); + break; + case 0x1: + parameterWrapper->set(detumbleParameter.omegaDetumbleStart); + break; + case 0x2: + parameterWrapper->set(detumbleParameter.omegaDetumbleEnd); + break; + default: + return INVALID_IDENTIFIER_ID; + } + break; + default: + return INVALID_IDENTIFIER_ID; + } + return returnvalue::OK; + } else { + return INVALID_DOMAIN_ID; + } }*/ -- 2.34.1 From 0a5bd6ef73bfadf8d2aaed4b5f54c97b713ba12c Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Fri, 14 Oct 2022 14:57:22 +0200 Subject: [PATCH 064/101] added sensor fusion logic for GYR --- mission/controller/acs/AcsParameters.cpp | 3 + mission/controller/acs/AcsParameters.h | 1 + mission/controller/acs/SensorProcessing.cpp | 75 ++++++++++++--------- 3 files changed, 47 insertions(+), 32 deletions(-) diff --git a/mission/controller/acs/AcsParameters.cpp b/mission/controller/acs/AcsParameters.cpp index ca1057bc..cc9959ab 100644 --- a/mission/controller/acs/AcsParameters.cpp +++ b/mission/controller/acs/AcsParameters.cpp @@ -226,6 +226,9 @@ AcsParameters::~AcsParameters() {} case 0x3: parameterWrapper->set(gyrHandlingParameters.gyr3orientationMatrix); break; + case 0x4: + parameterWrapper->set(gyrHandlingParameters.gyrFusionWeight); + break; default: return INVALID_IDENTIFIER_ID; } diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 6c72d9e5..97a31dd3 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -753,6 +753,7 @@ class AcsParameters /*: public HasParametersIF*/ { double gyr1orientationMatrix[3][3] = {{0, 0, -1}, {0, 1, 0}, {1, 0, 0}}; double gyr2orientationMatrix[3][3] = {{0, 0, -1}, {0, -1, 0}, {-1, 0, 0}}; double gyr3orientationMatrix[3][3] = {{0, 0, -1}, {0, 1, 0}, {1, 0, 0}}; + float gyrFusionWeight = 0.8; } gyrHandlingParameters; struct RwHandlingParameters { diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index 998927f6..a88d25ef 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -1,10 +1,3 @@ -/* - * SensorProcessing.cpp - * - * Created on: 7 Mar 2022 - * Author: Robin Marquardt - */ - #include "SensorProcessing.h" #include @@ -397,59 +390,77 @@ void SensorProcessing::processGyr( gyr3ValueBody[3] = {0, 0, 0}; bool validUnit[4] = {false, false, false, false}; - uint8_t validCount = 0; if (gyr0axXvalid && gyr0axYvalid && gyr0axZvalid) { const double gyr0Value[3] = {gyr0axXvalue, gyr0axYvalue, gyr0axZvalue}; MatrixOperations::multiply(gyrParameters->gyr0orientationMatrix[0], gyr0Value, gyr0ValueBody, 3, 3, 1); - validCount += 1; validUnit[0] = true; } if (gyr1axXvalid && gyr1axYvalid && gyr1axZvalid) { const double gyr1Value[3] = {gyr1axXvalue, gyr1axYvalue, gyr1axZvalue}; MatrixOperations::multiply(gyrParameters->gyr1orientationMatrix[0], gyr1Value, gyr1ValueBody, 3, 3, 1); - validCount += 1; validUnit[1] = true; } if (gyr2axXvalid && gyr2axYvalid && gyr2axZvalid) { const double gyr2Value[3] = {gyr2axXvalue, gyr2axYvalue, gyr2axZvalue}; MatrixOperations::multiply(gyrParameters->gyr2orientationMatrix[0], gyr2Value, gyr2ValueBody, 3, 3, 1); - validCount += 1; validUnit[2] = true; } if (gyr3axXvalid && gyr3axYvalid && gyr3axZvalid) { const double gyr3Value[3] = {gyr3axXvalue, gyr3axYvalue, gyr3axZvalue}; MatrixOperations::multiply(gyrParameters->gyr3orientationMatrix[0], gyr3Value, gyr3ValueBody, 3, 3, 1); - validCount += 1; validUnit[3] = true; } /* -------- SatRateEst: Middle Value ------- */ - double gyrValues[3][4] = { - {gyr0ValueBody[0], gyr1ValueBody[0], gyr2ValueBody[0], gyr3ValueBody[0]}, - {gyr0ValueBody[1], gyr1ValueBody[1], gyr2ValueBody[1], gyr3ValueBody[1]}, - {gyr0ValueBody[2], gyr1ValueBody[2], gyr2ValueBody[2], gyr3ValueBody[2]}}; - double gyrValidValues[3][validCount]; - uint8_t j = 0; - for (uint8_t i = 0; i < validCount; i++) { - if (validUnit[i]) { - gyrValidValues[0][j] = gyrValues[0][i]; - gyrValidValues[1][j] = gyrValues[1][i]; - gyrValidValues[2][j] = gyrValues[2][i]; - j += 1; + // take ADIS measurements, if both avail + // if just one ADIS measurement avail, perform sensor fusion + if (validUnit[0] && validUnit[2]) { + double gyr02ValuesSum[3]; + VectorOperations::add(gyr0ValueBody, gyr2ValueBody, gyr02ValuesSum, 3); + VectorOperations::mulScalar(gyr02ValuesSum, .5, satRatEst, 3); + } else if ((validUnit[0] || validUnit[2]) && !(validUnit[1] || validUnit[3])) { + if (validUnit[0]) { + satRatEst = gyr0ValueBody; + } else if (validUnit[2]) { + satRatEst = gyr2ValueBody; } - } - // Selection Sort - double gyrValidValuesSort[3][validCount]; - MathOperations::selectionSort(*gyrValidValues, *gyrValidValuesSort, 3, validCount); + } else if ((validUnit[1]) && (validUnit[3])) { + double gyr13ValuesSum[3]; + double gyr13ValuesMean[3]; + VectorOperations::add(gyr1ValueBody, gyr3ValueBody, gyr13ValuesSum, 3); + VectorOperations::mulScalar(gyr13ValuesSum, .5, gyr13ValuesMean, 3); + if (validUnit[0]) { + satRatEst[0] = (1 - gyrParameters->gyrFusionWeight) * gyrParameters->gyrFusionWeight * + gyr13ValuesMean[0] + + gyrParameters->gyrFusionWeight * gyr0ValueBody[0]; + satRatEst[1] = (1 - gyrParameters->gyrFusionWeight) * gyrParameters->gyrFusionWeight * + gyr13ValuesMean[1] + + gyrParameters->gyrFusionWeight * gyr0ValueBody[1]; + satRatEst[2] = (1 - gyrParameters->gyrFusionWeight) * gyrParameters->gyrFusionWeight * + gyr13ValuesMean[2] + + gyrParameters->gyrFusionWeight * gyr0ValueBody[2]; - uint8_t n = ceil(validCount / 2); - satRatEst[0] = gyrValidValuesSort[0][n]; - satRatEst[1] = gyrValidValuesSort[1][n]; - satRatEst[2] = gyrValidValuesSort[2][n]; + } else if (validUnit[2]) { + satRatEst[0] = (1 - gyrParameters->gyrFusionWeight) * gyrParameters->gyrFusionWeight * + gyr13ValuesMean[0] + + gyrParameters->gyrFusionWeight * gyr2ValueBody[0]; + satRatEst[1] = (1 - gyrParameters->gyrFusionWeight) * gyrParameters->gyrFusionWeight * + gyr13ValuesMean[1] + + gyrParameters->gyrFusionWeight * gyr2ValueBody[1]; + satRatEst[2] = (1 - gyrParameters->gyrFusionWeight) * gyrParameters->gyrFusionWeight * + gyr13ValuesMean[2] + + gyrParameters->gyrFusionWeight * gyr2ValueBody[2]; + } else + satRatEst = gyr13ValuesMean; + } else if (validUnit[1]) { + satRatEst = gyr1ValueBody; + } else if (validUnit[3]) { + satRatEst = gyr3ValueBody; + } *satRateEstValid = true; } -- 2.34.1 From 2d64892a81bb6f727b781624419ef1b453851ca1 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 17 Oct 2022 14:53:49 +0200 Subject: [PATCH 065/101] inserted fusion weight optimum --- 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 97a31dd3..15d4d84f 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -753,7 +753,7 @@ class AcsParameters /*: public HasParametersIF*/ { double gyr1orientationMatrix[3][3] = {{0, 0, -1}, {0, 1, 0}, {1, 0, 0}}; double gyr2orientationMatrix[3][3] = {{0, 0, -1}, {0, -1, 0}, {-1, 0, 0}}; double gyr3orientationMatrix[3][3] = {{0, 0, -1}, {0, 1, 0}, {1, 0, 0}}; - float gyrFusionWeight = 0.8; + float gyrFusionWeight = 0.93; } gyrHandlingParameters; struct RwHandlingParameters { -- 2.34.1 From 86450f9d66e0652f74b56b44d9f28ba6f32bd730 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 19 Oct 2022 11:00:46 +0200 Subject: [PATCH 066/101] Added DataSets for all OutputValues/Sensors --- .../AcsCtrlDefinitions.h | 163 +++++++++++++++++- 1 file changed, 155 insertions(+), 8 deletions(-) diff --git a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h index 1b38e033..c122be43 100644 --- a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h +++ b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h @@ -8,16 +8,35 @@ namespace acsctrl { -enum SetIds : uint32_t { MGM_SENSOR_DATA, SUS_SENSOR_DATA }; +enum SetIds : uint32_t { + MGM_SENSOR_DATA, + MGM_PROCESSED_DATA, + SUS_SENSOR_DATA, + SUS_PROCESSED_DATA, + GYR_SENSOR_DATA, + GYR_PROCESSED_DATA, + GPS_SENSOR_DATA, + MEKF_DATA +}; enum PoolIds : lp_id_t { + // MGM Raw MGM_0_LIS3_UT, MGM_1_RM3100_UT, MGM_2_LIS3_UT, MGM_3_RM3100_UT, MGM_IMTQ_CAL_NT, MGM_IMTQ_CAL_ACT_STATUS, - + // MGM Processed + MGM_0_VEC, + MGM_1_VEC, + MGM_2_VEC, + MGM_3_VEC, + MGM_4_VEC, + MGM_VEC_TOT, + MGM_VEC_TOT_DERIVATIVE, + MAG_IGRF_MODEL, + // SUS Raw SUS_0_N_LOC_XFYFZM_PT_XF, SUS_6_R_LOC_XFYBZM_PT_XF, @@ -35,15 +54,54 @@ enum PoolIds : lp_id_t { SUS_5_N_LOC_XFYMZB_PT_ZB, SUS_11_R_LOC_XBYMZB_PT_ZB, + // SUS Processed + SUS_0_VEC, + SUS_1_VEC, + SUS_2_VEC, + SUS_3_VEC, + SUS_4_VEC, + SUS_5_VEC, + SUS_6_VEC, + SUS_7_VEC, + SUS_8_VEC, + SUS_9_VEC, + SUS_10_VEC, + SUS_11_VEC, + SUS_VEC_TOT, + SUS_VEC_TOT_DERIVATIVE, + SUN_IJK_MODEL, + // GYR Raw + GYR_0_ADIS, + GYR_1_L3, + GYR_2_ADIS, + GYR_3_L3, + // GYR Processed + GYR_0_VEC, + GYR_1_VEC, + GYR_2_VEC, + GYR_3_VEC, + GYR_VEC_TOT, + // GPS PROCESSED + GC_LATITUDE, + GD_LONGITUDE, + // MEKF + SAT_ROT_RATE_MEKF, + QUAT_MEKF, }; -static constexpr uint8_t MGM_SET_ENTRIES = 10; -static constexpr uint8_t SUS_SET_ENTRIES = 12; +static constexpr uint8_t MGM_SET_RAW_ENTRIES = 10; +static constexpr uint8_t MGM_SET_PROCESSED_ENTRIES = 7 * sizeof(float) + 1 * sizeof(double); +static constexpr uint8_t SUS_SET_RAW_ENTRIES = 12; +static constexpr uint8_t SUS_SET_PROCESSED_ENTRIES = 14 * sizeof(float) + 1 * sizeof(double); +static constexpr uint8_t GYR_SET_RAW_ENTRIES = 2 * sizeof(float) + 2 * sizeof(double); +static constexpr uint8_t GYR_SET_PROCESSED_ENTRIES = 5 * sizeof(double); +static constexpr uint8_t GPS_SET_PROCESSED_ENTRIES = 2 * sizeof(double); +static constexpr uint8_t MEKF_SET_ENTRIES = 14 * sizeof(float) + 1 * sizeof(double); /** * @brief Raw MGM sensor data. Includes the IMTQ sensor data and actuator status. */ -class MgmDataRaw : public StaticLocalDataSet { +class MgmDataRaw : public StaticLocalDataSet { public: MgmDataRaw(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, MGM_SENSOR_DATA) {} @@ -60,7 +118,24 @@ class MgmDataRaw : public StaticLocalDataSet { private: }; -class SusDataRaw : public StaticLocalDataSet { +class MgmDataProcessed : public StaticLocalDataSet { + public: + MgmDataProcessed(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, MGM_PROCESSED_DATA) {} + + lp_vec_t mgm0vec = lp_vec_t(sid.objectId, MGM_0_VEC, this); + lp_vec_t mgm1vec = lp_vec_t(sid.objectId, MGM_1_VEC, this); + lp_vec_t mgm2vec = lp_vec_t(sid.objectId, MGM_2_VEC, this); + lp_vec_t mgm3vec = lp_vec_t(sid.objectId, MGM_3_VEC, this); + lp_vec_t mgm4vec = lp_vec_t(sid.objectId, MGM_4_VEC, this); + lp_vec_t mgmVecTot = lp_vec_t(sid.objectId, MGM_VEC_TOT, this); + lp_vec_t mgmVecTotDerivative = + lp_vec_t(sid.objectId, MGM_VEC_TOT_DERIVATIVE, this); + lp_vec_t magIgrfModel = lp_vec_t(sid.objectId, MAG_IGRF_MODEL, this); + + private: +}; + +class SusDataRaw : public StaticLocalDataSet { public: SusDataRaw(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, SUS_SENSOR_DATA) {} @@ -74,8 +149,80 @@ class SusDataRaw : public StaticLocalDataSet { lp_vec_t sus7 = lp_vec_t(sid.objectId, SUS_7_R_LOC_XBYBZM_PT_XB, this); lp_vec_t sus8 = lp_vec_t(sid.objectId, SUS_8_R_LOC_XBYBZB_PT_YB, this); lp_vec_t sus9 = lp_vec_t(sid.objectId, SUS_9_R_LOC_XBYBZB_PT_YF, this); - lp_vec_t sus10 = lp_vec_t(sid.objectId, SUS_10_N_LOC_XMYBZF_PT_ZF, this); - lp_vec_t sus11 = lp_vec_t(sid.objectId, SUS_11_R_LOC_XBYMZB_PT_ZB, this); + lp_vec_t sus10 = + lp_vec_t(sid.objectId, SUS_10_N_LOC_XMYBZF_PT_ZF, this); + lp_vec_t sus11 = + lp_vec_t(sid.objectId, SUS_11_R_LOC_XBYMZB_PT_ZB, this); + + private: +}; + +class SusDataProcessed : public StaticLocalDataSet { + public: + SusDataProcessed(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, SUS_PROCESSED_DATA) {} + + lp_vec_t sus0vec = lp_vec_t(sid.objectId, SUS_0_VEC, this); + lp_vec_t sus1vec = lp_vec_t(sid.objectId, SUS_1_VEC, this); + lp_vec_t sus2vec = lp_vec_t(sid.objectId, SUS_2_VEC, this); + lp_vec_t sus3vec = lp_vec_t(sid.objectId, SUS_3_VEC, this); + lp_vec_t sus4vec = lp_vec_t(sid.objectId, SUS_4_VEC, this); + lp_vec_t sus5vec = lp_vec_t(sid.objectId, SUS_5_VEC, this); + lp_vec_t sus6vec = lp_vec_t(sid.objectId, SUS_6_VEC, this); + lp_vec_t sus7vec = lp_vec_t(sid.objectId, SUS_7_VEC, this); + lp_vec_t sus8vec = lp_vec_t(sid.objectId, SUS_8_VEC, this); + lp_vec_t sus9vec = lp_vec_t(sid.objectId, SUS_8_VEC, this); + lp_vec_t sus10vec = lp_vec_t(sid.objectId, SUS_8_VEC, this); + lp_vec_t sus11vec = lp_vec_t(sid.objectId, SUS_8_VEC, this); + lp_vec_t susVecTot = lp_vec_t(sid.objectId, SUS_VEC_TOT, this); + lp_vec_t susVecTotDerivative = + lp_vec_t(sid.objectId, SUS_VEC_TOT_DERIVATIVE, this); + lp_vec_t sunIjkModel = lp_vec_t(sid.objectId, SUN_IJK_MODEL, this); + + private: +}; + +class GyrDataRaw : public StaticLocalDataSet { + public: + GyrDataRaw(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, GYR_SENSOR_DATA) {} + + lp_vec_t gyr0Adis = lp_vec_t(sid.objectId, GYR_0_ADIS, this); + lp_vec_t gyr1L3 = lp_vec_t(sid.objectId, GYR_1_L3, this); + lp_vec_t gyr2Adis = lp_vec_t(sid.objectId, GYR_2_ADIS, this); + lp_vec_t gyr3L3 = lp_vec_t(sid.objectId, GYR_3_L3, this); + + private: +}; + +class GyrDataProcessed : public StaticLocalDataSet { + public: + GyrDataProcessed(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, GYR_PROCESSED_DATA) {} + + lp_vec_t gyr0vec = lp_vec_t(sid.objectId, GYR_0_VEC, this); + lp_vec_t gyr1vec = lp_vec_t(sid.objectId, GYR_1_VEC, this); + lp_vec_t gyr2vec = lp_vec_t(sid.objectId, GYR_2_VEC, this); + lp_vec_t gyr3vec = lp_vec_t(sid.objectId, GYR_3_VEC, this); + lp_vec_t gyrVecTot = lp_vec_t(sid.objectId, GYR_VEC_TOT, this); + + private: +}; + +class GpsDataProcessed : public StaticLocalDataSet { + public: + GpsDataProcessed(HasLocalDataPoolIF* hkOwner) + : StaticLocalDataSet(hkOwner, GPS_SET_PROCESSED_ENTRIES) {} + + lp_var_t gcLatitude = lp_var_t(sid.objectId, GC_LATITUDE, this); + lp_var_t gdLongitude = lp_var_t(sid.objectId, GD_LONGITUDE, this); + + private: +}; + +class MekfData : public StaticLocalDataSet { + public: + MekfData(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, MEKF_DATA) {} + + lp_vec_t quatMekf = lp_vec_t(sid.objectId, QUAT_MEKF, this); + lp_vec_t satRotRateMekf = lp_vec_t(sid.objectId, SAT_ROT_RATE_MEKF, this); private: }; -- 2.34.1 From c50f8c716fad875314c94c0c01018b810c5c72fe Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 19 Oct 2022 11:01:27 +0200 Subject: [PATCH 067/101] amended GYR sensor fusion. replaced MGM sensor fusion --- mission/controller/acs/SensorProcessing.cpp | 104 ++++++++++---------- 1 file changed, 50 insertions(+), 54 deletions(-) diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index a88d25ef..a6571496 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -42,9 +42,8 @@ bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const mgm3ValueCalib[3] = {0, 0, 0}, mgm4ValueCalib[3] = {0, 0, 0}; float mgm0ValueBody[3] = {0, 0, 0}, mgm1ValueBody[3] = {0, 0, 0}, mgm2ValueBody[3] = {0, 0, 0}, mgm3ValueBody[3] = {0, 0, 0}, mgm4ValueBody[3] = {0, 0, 0}; + float sensorFusionNumerator[3] = {0, 0, 0}, sensorFusionDenominator[3] = {0, 0, 0}; - bool validUnit[5] = {false, false, false, false, false}; - uint8_t validCount = 0; if (mgm0valid) { VectorOperations::subtract(mgm0Value, mgmParameters->mgm0hardIronOffset, mgm0ValueNoBias, 3); @@ -52,8 +51,10 @@ bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const mgm0ValueCalib, 3, 3, 1); MatrixOperations::multiply(mgmParameters->mgm0orientationMatrix[0], mgm0ValueCalib, mgm0ValueBody, 3, 3, 1); - validCount += 1; - validUnit[0] = true; + for (uint8_t i = 0; i < 3; i++) { + sensorFusionNumerator[i] += mgm0ValueBody[i] / mgmParameters->mgm02variance[i]; + sensorFusionDenominator[i] += 1 / mgmParameters->mgm02variance[i]; + } } if (mgm1valid) { VectorOperations::subtract(mgm1Value, mgmParameters->mgm1hardIronOffset, mgm1ValueNoBias, @@ -62,8 +63,10 @@ bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const mgm1ValueCalib, 3, 3, 1); MatrixOperations::multiply(mgmParameters->mgm1orientationMatrix[0], mgm1ValueCalib, mgm1ValueBody, 3, 3, 1); - validCount += 1; - validUnit[1] = true; + for (uint8_t i = 0; i < 3; i++) { + sensorFusionNumerator[i] += mgm1ValueBody[i] / mgmParameters->mgm13variance[i]; + sensorFusionDenominator[i] += 1 / mgmParameters->mgm13variance[i]; + } } if (mgm2valid) { VectorOperations::subtract(mgm2Value, mgmParameters->mgm2hardIronOffset, mgm2ValueNoBias, @@ -72,8 +75,10 @@ bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const mgm2ValueCalib, 3, 3, 1); MatrixOperations::multiply(mgmParameters->mgm2orientationMatrix[0], mgm2ValueCalib, mgm2ValueBody, 3, 3, 1); - validCount += 1; - validUnit[2] = true; + for (uint8_t i = 0; i < 3; i++) { + sensorFusionNumerator[i] += mgm2ValueBody[i] / mgmParameters->mgm02variance[i]; + sensorFusionDenominator[i] += 1 / mgmParameters->mgm02variance[i]; + } } if (mgm3valid) { VectorOperations::subtract(mgm3Value, mgmParameters->mgm3hardIronOffset, mgm3ValueNoBias, @@ -82,8 +87,10 @@ bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const mgm3ValueCalib, 3, 3, 1); MatrixOperations::multiply(mgmParameters->mgm3orientationMatrix[0], mgm3ValueCalib, mgm3ValueBody, 3, 3, 1); - validCount += 1; - validUnit[3] = true; + for (uint8_t i = 0; i < 3; i++) { + sensorFusionNumerator[i] += mgm3ValueBody[i] / mgmParameters->mgm13variance[i]; + sensorFusionDenominator[i] += 1 / mgmParameters->mgm13variance[i]; + } } if (mgm4valid) { VectorOperations::subtract(mgm4Value, mgmParameters->mgm4hardIronOffset, mgm4ValueNoBias, @@ -92,33 +99,17 @@ bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const mgm4ValueCalib, 3, 3, 1); MatrixOperations::multiply(mgmParameters->mgm4orientationMatrix[0], mgm4ValueCalib, mgm4ValueBody, 3, 3, 1); - validCount += 1; - validUnit[4] = true; - } - - /* -------- MagFieldEst: Middle Value ------- */ - float mgmValues[3][5] = { - {mgm0ValueBody[0], mgm1ValueBody[0], mgm2ValueBody[0], mgm3ValueBody[0], mgm4ValueBody[0]}, - {mgm0ValueBody[1], mgm1ValueBody[1], mgm2ValueBody[1], mgm3ValueBody[1], mgm4ValueBody[1]}, - {mgm0ValueBody[2], mgm1ValueBody[2], mgm2ValueBody[2], mgm3ValueBody[2], mgm4ValueBody[2]}}; - double mgmValidValues[3][validCount]; - uint8_t j = 0; - for (uint8_t i = 0; i < validCount; i++) { - if (validUnit[i]) { - mgmValidValues[0][j] = mgmValues[0][i]; - mgmValidValues[1][j] = mgmValues[1][i]; - mgmValidValues[2][j] = mgmValues[2][i]; - j += 1; + for (uint8_t i = 0; i < 3; i++) { + sensorFusionNumerator[i] += mgm4ValueBody[i] / mgmParameters->mgm4variance[i]; + sensorFusionDenominator[i] += 1 / mgmParameters->mgm4variance[i]; } } - // Selection Sort - double mgmValidValuesSort[3][validCount]; - MathOperations::selectionSort(*mgmValidValues, *mgmValidValuesSort, 3, validCount); - - uint8_t n = ceil(validCount / 2); - magFieldEst[0] = mgmValidValuesSort[0][n]; - magFieldEst[1] = mgmValidValuesSort[1][n]; - magFieldEst[2] = mgmValidValuesSort[2][n]; + for (uint8_t i = 0; i < 3; i++) { + magFieldEst[i] = sensorFusionNumerator[i] / sensorFusionDenominator[i]; + } + sif::debug << "magFeildEst: " << magFieldEst[0] << " , " << magFieldEst[1] << " , " + << magFieldEst[2] << std::endl; + ; validMagField = true; //-----------------------Mag Rate Computation --------------------------------------------------- @@ -434,26 +425,31 @@ void SensorProcessing::processGyr( VectorOperations::add(gyr1ValueBody, gyr3ValueBody, gyr13ValuesSum, 3); VectorOperations::mulScalar(gyr13ValuesSum, .5, gyr13ValuesMean, 3); if (validUnit[0]) { - satRatEst[0] = (1 - gyrParameters->gyrFusionWeight) * gyrParameters->gyrFusionWeight * - gyr13ValuesMean[0] + - gyrParameters->gyrFusionWeight * gyr0ValueBody[0]; - satRatEst[1] = (1 - gyrParameters->gyrFusionWeight) * gyrParameters->gyrFusionWeight * - gyr13ValuesMean[1] + - gyrParameters->gyrFusionWeight * gyr0ValueBody[1]; - satRatEst[2] = (1 - gyrParameters->gyrFusionWeight) * gyrParameters->gyrFusionWeight * - gyr13ValuesMean[2] + - gyrParameters->gyrFusionWeight * gyr0ValueBody[2]; - + satRatEst[0] = + ((gyr0ValueBody[0] / gyrParameters->gyr02variance[0]) + + (gyr13ValuesMean[0] / gyrParameters->gyr13variance[0])) / + ((1 / gyrParameters->gyr02variance[0]) + (1 / gyrParameters->gyr13variance[0])); + satRatEst[1] = + ((gyr0ValueBody[1] / gyrParameters->gyr02variance[1]) + + (gyr13ValuesMean[1] / gyrParameters->gyr13variance[1])) / + ((1 / gyrParameters->gyr02variance[1]) + (1 / gyrParameters->gyr13variance[1])); + satRatEst[2] = + ((gyr0ValueBody[2] / gyrParameters->gyr02variance[2]) + + (gyr13ValuesMean[2] / gyrParameters->gyr13variance[2])) / + ((1 / gyrParameters->gyr02variance[2]) + (1 / gyrParameters->gyr13variance[2])); } else if (validUnit[2]) { - satRatEst[0] = (1 - gyrParameters->gyrFusionWeight) * gyrParameters->gyrFusionWeight * - gyr13ValuesMean[0] + - gyrParameters->gyrFusionWeight * gyr2ValueBody[0]; - satRatEst[1] = (1 - gyrParameters->gyrFusionWeight) * gyrParameters->gyrFusionWeight * - gyr13ValuesMean[1] + - gyrParameters->gyrFusionWeight * gyr2ValueBody[1]; - satRatEst[2] = (1 - gyrParameters->gyrFusionWeight) * gyrParameters->gyrFusionWeight * - gyr13ValuesMean[2] + - gyrParameters->gyrFusionWeight * gyr2ValueBody[2]; + satRatEst[0] = + ((gyr2ValueBody[0] / gyrParameters->gyr02variance[0]) + + (gyr13ValuesMean[0] / gyrParameters->gyr13variance[0])) / + ((1 / gyrParameters->gyr02variance[0]) + (1 / gyrParameters->gyr13variance[0])); + satRatEst[1] = + ((gyr2ValueBody[1] / gyrParameters->gyr02variance[1]) + + (gyr13ValuesMean[1] / gyrParameters->gyr13variance[1])) / + ((1 / gyrParameters->gyr02variance[1]) + (1 / gyrParameters->gyr13variance[1])); + satRatEst[2] = + ((gyr2ValueBody[2] / gyrParameters->gyr02variance[2]) + + (gyr13ValuesMean[2] / gyrParameters->gyr13variance[2])) / + ((1 / gyrParameters->gyr02variance[2]) + (1 / gyrParameters->gyr13variance[2])); } else satRatEst = gyr13ValuesMean; } else if (validUnit[1]) { -- 2.34.1 From 5c2266e2143df464ba2ad3fde5d18ffa52903692 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 19 Oct 2022 11:01:53 +0200 Subject: [PATCH 068/101] added variances for sensors for sensor fusion --- mission/controller/acs/AcsParameters.h | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 15d4d84f..f5b72252 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -54,6 +54,9 @@ class AcsParameters /*: public HasParametersIF*/ { {15.67482e-2, -6.958760e-2, 94.50124e-2}}; float mgm3softIronInverse[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}}; float mgm4softIronInverse[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}}; + float mgm02variance[3] = {1, 1, 1}; + float mgm13variance[3] = {1, 1, 1}; + float mgm4variance[3] = {1, 1, 1}; } mgmHandlingParameters; @@ -753,7 +756,12 @@ class AcsParameters /*: public HasParametersIF*/ { double gyr1orientationMatrix[3][3] = {{0, 0, -1}, {0, 1, 0}, {1, 0, 0}}; double gyr2orientationMatrix[3][3] = {{0, 0, -1}, {0, -1, 0}, {-1, 0, 0}}; double gyr3orientationMatrix[3][3] = {{0, 0, -1}, {0, 1, 0}, {1, 0, 0}}; - float gyrFusionWeight = 0.93; + // var = sqrt(sigma), 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 * sqrt(2), 2), // RND_x = 3.0e-3 deg/s/sqrt(Hz) rms + pow(3.0e-3 * sqrt(2), 2), // RND_y = 3.0e-3 deg/s/sqrt(Hz) rms + pow(4.3e-3 * sqrt(2), 2)}; // RND_z = 4.3e-3 deg/s/sqrt(Hz) rms + float gyr13variance[3] = {pow(11e-3, 2), pow(11e-3, 2), pow(11e-3, 2)}; } gyrHandlingParameters; struct RwHandlingParameters { -- 2.34.1 From deb7c4e5008a30b0553290caa4d73660f4d3a5b7 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 20 Oct 2022 11:07:45 +0200 Subject: [PATCH 069/101] added saftCtrl to acsController --- mission/controller/AcsController.cpp | 66 ++++- mission/controller/AcsController.h | 3 +- mission/controller/acs/control/SafeCtrl.cpp | 262 ++++++++++---------- mission/controller/acs/control/SafeCtrl.h | 69 +++--- 4 files changed, 221 insertions(+), 179 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 856a0034..22c871fd 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -8,6 +8,7 @@ AcsController::AcsController(object_id_t objectId) navigation(&acsParameters), actuatorCmd(&acsParameters), guidance(&acsParameters), + safeCtrl(&acsParameters), detumble(&acsParameters), ptgCtrl(&acsParameters), detumbleCounter{0}, @@ -35,7 +36,7 @@ void AcsController::performControlOperation() { if (mode != MODE_OFF) { switch (submode) { case SUBMODE_SAFE: - // performSafe(); + performSafe(); break; case SUBMODE_DETUMBLE: @@ -72,7 +73,66 @@ void AcsController::performControlOperation() { // DEBUG END } -void AcsController::performSafe() {} +void AcsController::performSafe() { + // Concept: SAFE MODE WITH MEKF + // -do the sensor processing, maybe is does make more sense do call this class function in + // another place since we have to do it for every mode regardless of safe or not + + ACS::SensorValues sensorValues; + ACS::OutputValues outputValues; + + timeval now; // We need to give the actual time here + sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); + ReturnValue_t validMekf; + navigation.useMekf(&sensorValues, &outputValues, &validMekf); // DOES THIS WORK WITH VALID? + // Give desired satellite rate and sun direction to align + double satRateSafe[3] = {0, 0, 0}, sunTargetDir[3] = {0, 0, 0}; + guidance.getTargetParamsSafe(sunTargetDir, satRateSafe); + // IF MEKF is working + double magMomMtq[3] = {0, 0, 0}; + bool magMomMtqValid = false; + if (validMekf == returnvalue::OK) { + safeCtrl.safeMekf(now, (outputValues.quatMekfBJ), &(outputValues.quatMekfBJValid), + (outputValues.magFieldModel), &(outputValues.magFieldModelValid), + (outputValues.sunDirModel), &(outputValues.sunDirModelValid), + (outputValues.satRateMekf), &(outputValues.satRateMekfValid), sunTargetDir, + satRateSafe, magMomMtq, &magMomMtqValid); + } else { + safeCtrl.safeNoMekf(now, outputValues.sunDirEst, &outputValues.sunDirEstValid, + outputValues.sunVectorDerivative, &(outputValues.sunVectorDerivativeValid), + outputValues.magFieldEst, &(outputValues.magFieldEstValid), + outputValues.magneticFieldVectorDerivative, + &(outputValues.magneticFieldVectorDerivativeValid), sunTargetDir, + satRateSafe, magMomMtq, &magMomMtqValid); + } + + double dipolCmdUnits[3] = {0, 0, 0}; + actuatorCmd.cmdDipolMtq(magMomMtq, dipolCmdUnits); + + // Detumble check and switch + if (outputValues.satRateMekfValid && VectorOperations::norm(outputValues.satRateMekf, 3) > + acsParameters.detumbleParameter.omegaDetumbleStart) { + detumbleCounter++; + } + + else if (outputValues.satRateEstValid && + VectorOperations::norm(outputValues.satRateEst, 3) > + acsParameters.detumbleParameter.omegaDetumbleStart) { + detumbleCounter++; + + } + + else { + detumbleCounter = 0; + } + + if (detumbleCounter > acsParameters.detumbleParameter.detumblecounter) { + submode = SUBMODE_DETUMBLE; + detumbleCounter = 0; + } + + // commanding.magnetorquesDipol(); +} void AcsController::performDetumble() { ACS::SensorValues sensorValues; @@ -293,6 +353,8 @@ void AcsController::copySusData() { PoolReadGuard pg(&susSets[9]); if (pg.getReadResult() == returnvalue::OK) { std::memcpy(susData.sus9.value, susSets[9].channels.value, 6 * sizeof(uint16_t)); + sif::debug << susData.sus9.isValid() << std::endl; + sif::debug << susSets[9].channels.isValid() << std::endl; } } { diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index c23adfc1..a8ae9daa 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -11,6 +11,7 @@ #include "acs/SensorProcessing.h" #include "acs/control/Detumble.h" #include "acs/control/PtgCtrl.h" +#include "acs/control/SafeCtrl.h" #include "controllerdefinitions/AcsCtrlDefinitions.h" #include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" #include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" @@ -29,7 +30,6 @@ class AcsController : public ExtendedControllerBase { static const Submode_t SUBMODE_PTG_NADIR = 5; protected: - void performSafe(); void performDetumble(); void performPointingCtrl(); @@ -41,6 +41,7 @@ class AcsController : public ExtendedControllerBase { ActuatorCmd actuatorCmd; Guidance guidance; + SafeCtrl safeCtrl; Detumble detumble; PtgCtrl ptgCtrl; diff --git a/mission/controller/acs/control/SafeCtrl.cpp b/mission/controller/acs/control/SafeCtrl.cpp index 32029ad7..c892fc05 100644 --- a/mission/controller/acs/control/SafeCtrl.cpp +++ b/mission/controller/acs/control/SafeCtrl.cpp @@ -6,182 +6,172 @@ */ #include "SafeCtrl.h" -#include "../util/MathOperations.h" -#include + #include #include #include #include +#include +#include "../util/MathOperations.h" -SafeCtrl::SafeCtrl(AcsParameters *acsParameters_){ - loadAcsParameters(acsParameters_); - MatrixOperations::multiplyScalar(*(inertiaEIVE->inertiaMatrix), 10, *gainMatrixInertia, 3, 3); +SafeCtrl::SafeCtrl(AcsParameters *acsParameters_) { + loadAcsParameters(acsParameters_); + MatrixOperations::multiplyScalar(*(inertiaEIVE->inertiaMatrix), 10, *gainMatrixInertia, 3, + 3); } -SafeCtrl::~SafeCtrl(){ +SafeCtrl::~SafeCtrl() {} -} - -void SafeCtrl::loadAcsParameters(AcsParameters *acsParameters_){ - safeModeControllerParameters = &(acsParameters_->safeModeControllerParameters); - inertiaEIVE = &(acsParameters_->inertiaEIVE); +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, bool *rateMekfValid, - double *sunDirRef, double *satRatRef, - double *outputMagMomB, bool *outputValid){ + double *magFieldModel, bool *magFieldModelValid, + double *sunDirModel, bool *sunDirModelValid, double *satRateMekf, + bool *rateMekfValid, double *sunDirRef, double *satRatRef, + double *outputMagMomB, bool *outputValid) { + if (!(*quatBJValid) || !(*magFieldModelValid) || !(*sunDirModelValid) || !(*rateMekfValid)) { + *outputValid = false; + return SAFECTRL_MEKF_INPUT_INVALID; + } - if ( !(*quatBJValid) || !(*magFieldModelValid) || !(*sunDirModelValid) || - !(*rateMekfValid)) { - *outputValid = false; - return SAFECTRL_MEKF_INPUT_INVALID; - } + double kRate = 0, kAlign = 0; + kRate = safeModeControllerParameters->k_rate_mekf; + kAlign = safeModeControllerParameters->k_align_mekf; - double kRate = 0, kAlign = 0; - kRate = safeModeControllerParameters->k_rate_mekf; - kAlign = 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}}; + MathOperations::dcmFromQuat(quatBJ, *dcmBJ); + double sunDirB[3] = {0, 0, 0}, magFieldB[3] = {0, 0, 0}; + MatrixOperations::multiply(*dcmBJ, sunDirModel, sunDirB, 3, 3, 1); + MatrixOperations::multiply(*dcmBJ, magFieldModel, magFieldB, 3, 3, 1); -// Calc sunDirB ,magFieldB with mekf output and model - double dcmBJ[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; - MathOperations::dcmFromQuat(quatBJ, *dcmBJ); - double sunDirB[3] = {0,0,0}, magFieldB[3] = {0,0,0}; - MatrixOperations::multiply(*dcmBJ, sunDirModel, sunDirB, 3, 3, 1); - MatrixOperations::multiply(*dcmBJ, magFieldModel, magFieldB, 3, 3, 1); + double crossSun[3] = {0, 0, 0}; - double crossSun[3] = {0, 0, 0}; + VectorOperations::cross(sunDirRef, sunDirB, crossSun); + double normCrossSun = VectorOperations::norm(crossSun, 3); - VectorOperations::cross(sunDirRef, sunDirB, crossSun); - double normCrossSun = VectorOperations::norm(crossSun, 3); + // calc angle alpha between sunDirRef and sunDIr + double alpha = 0, dotSun = 0; + dotSun = VectorOperations::dot(sunDirRef, sunDirB); + alpha = acos(dotSun); -// calc angle alpha between sunDirRef and sunDIr - double alpha = 0, dotSun = 0; - dotSun = VectorOperations::dot(sunDirRef, sunDirB); - alpha = acos(dotSun); + // Law Torque calculations + double torqueCmd[3] = {0, 0, 0}, torqueAlign[3] = {0, 0, 0}, torqueRate[3] = {0, 0, 0}, + torqueAll[3] = {0, 0, 0}; -// Law Torque calculations - double torqueCmd[3] = {0, 0, 0}, torqueAlign[3] = {0, 0, 0}, - torqueRate[3] = {0, 0, 0}, torqueAll[3] = {0, 0, 0}; + double scalarFac = 0; + scalarFac = kAlign * alpha / normCrossSun; + VectorOperations::mulScalar(crossSun, scalarFac, torqueAlign, 3); - double scalarFac = 0; - scalarFac = kAlign * alpha / normCrossSun; - VectorOperations::mulScalar(crossSun, scalarFac, torqueAlign, 3); + double rateSafeMode[3] = {0, 0, 0}; + VectorOperations::subtract(satRateMekf, satRatRef, rateSafeMode, 3); + VectorOperations::mulScalar(rateSafeMode, -kRate, torqueRate, 3); - double rateSafeMode[3] = {0,0,0}; - VectorOperations::subtract(satRateMekf, satRatRef, rateSafeMode, 3); - VectorOperations::mulScalar(rateSafeMode, -kRate, torqueRate, 3); + VectorOperations::add(torqueRate, torqueAlign, torqueAll, 3); + // Adding factor of inertia for axes + MatrixOperations::multiply(*gainMatrixInertia, torqueAll, torqueCmd, 3, 3, 1); - VectorOperations::add(torqueRate, torqueAlign, torqueAll, 3); -// Adding factor of inertia for axes - MatrixOperations::multiply(*gainMatrixInertia, torqueAll, torqueCmd, 3, 3, 1); - -// MagMom B (orthogonal torque) - double torqueMgt[3] = {0,0,0}; - VectorOperations::cross(magFieldB, torqueCmd, torqueMgt); - double normMag = VectorOperations::norm(magFieldB, 3); - VectorOperations::mulScalar(torqueMgt, 1/pow(normMag,2), outputMagMomB, 3); - *outputValid = true; - - return returnvalue::OK; + // MagMom B (orthogonal torque) + double torqueMgt[3] = {0, 0, 0}; + VectorOperations::cross(magFieldB, torqueCmd, torqueMgt); + double normMag = VectorOperations::norm(magFieldB, 3); + VectorOperations::mulScalar(torqueMgt, 1 / pow(normMag, 2), outputMagMomB, 3); + *outputValid = true; + return returnvalue::OK; } // Will be the version in worst case scenario in event of no working MEKF (nor RMUs) -void SafeCtrl::safeNoMekf(timeval now, double *susDirB, bool *susDirBValid, - double *sunRateB, bool *sunRateBValid, - double *magFieldB, bool *magFieldBValid, - double *magRateB, bool *magRateBValid, - double *sunDirRef, double *satRateRef, - double *outputMagMomB, bool *outputValid){ +void SafeCtrl::safeNoMekf(timeval now, double *susDirB, bool *susDirBValid, double *sunRateB, + bool *sunRateBValid, double *magFieldB, bool *magFieldBValid, + double *magRateB, bool *magRateBValid, double *sunDirRef, + double *satRateRef, double *outputMagMomB, bool *outputValid) { + // Check for invalid Inputs + if (!susDirBValid || !magFieldBValid || !magRateBValid) { + *outputValid = false; + return; + } -// Check for invalid Inputs - if ( !susDirBValid || !magFieldBValid || !magRateBValid) { - *outputValid = false; - return; - } + // normalize sunDir and magDir + double magDirB[3] = {0, 0, 0}; + VectorOperations::normalize(magFieldB, magDirB, 3); + VectorOperations::normalize(susDirB, susDirB, 3); -// normalize sunDir and magDir - double magDirB[3] = {0, 0, 0}; - VectorOperations::normalize(magFieldB, magDirB, 3); - VectorOperations::normalize(susDirB, susDirB, 3); + // Cosinus angle between sunDir and magDir + double cosAngleSunMag = VectorOperations::dot(magDirB, susDirB); -// Cosinus angle between sunDir and magDir - double cosAngleSunMag = VectorOperations::dot(magDirB, susDirB); + // Rate parallel to sun direction and magnetic field direction + double rateParaSun = 0, rateParaMag = 0; + double dotSunRateMag = 0, dotmagRateSun = 0, rateFactor = 0; + dotSunRateMag = VectorOperations::dot(sunRateB, magDirB); + dotmagRateSun = VectorOperations::dot(magRateB, susDirB); + rateFactor = 1 - pow(cosAngleSunMag, 2); + rateParaSun = (dotmagRateSun + cosAngleSunMag * dotSunRateMag) / rateFactor; + rateParaMag = (dotSunRateMag + cosAngleSunMag * dotmagRateSun) / rateFactor; -// Rate parallel to sun direction and magnetic field direction - double rateParaSun = 0, rateParaMag = 0; - double dotSunRateMag = 0, dotmagRateSun = 0, - rateFactor = 0; - dotSunRateMag = VectorOperations::dot(sunRateB, magDirB); - dotmagRateSun = VectorOperations::dot(magRateB, susDirB); - rateFactor = 1 - pow(cosAngleSunMag,2); - rateParaSun = ( dotmagRateSun + cosAngleSunMag * dotSunRateMag ) / rateFactor; - rateParaMag = ( dotSunRateMag + cosAngleSunMag * dotmagRateSun ) / rateFactor; + // Full rate or estimate + double estSatRate[3] = {0, 0, 0}; + double estSatRateMag[3] = {0, 0, 0}, estSatRateSun[3] = {0, 0, 0}; + VectorOperations::mulScalar(susDirB, rateParaSun, estSatRateSun, 3); + VectorOperations::add(sunRateB, estSatRateSun, estSatRateSun, 3); + VectorOperations::mulScalar(magDirB, rateParaMag, estSatRateMag, 3); + VectorOperations::add(magRateB, estSatRateMag, estSatRateMag, 3); + VectorOperations::add(estSatRateSun, estSatRateMag, estSatRate, 3); + VectorOperations::mulScalar(estSatRate, 0.5, estSatRate, 3); -// Full rate or estimate - double estSatRate[3] = {0, 0, 0}; - double estSatRateMag[3] = {0, 0, 0}, estSatRateSun[3] = {0, 0, 0}; - VectorOperations::mulScalar(susDirB, rateParaSun, estSatRateSun, 3); - VectorOperations::add(sunRateB, estSatRateSun, estSatRateSun, 3); - VectorOperations::mulScalar(magDirB, rateParaMag, estSatRateMag, 3); - VectorOperations::add(magRateB, estSatRateMag, estSatRateMag, 3); - VectorOperations::add(estSatRateSun, estSatRateMag, estSatRate, 3); - VectorOperations::mulScalar(estSatRate, 0.5, estSatRate, 3); + /* Only valid if angle between sun direction and magnetic field direction + is sufficiently large */ -/* Only valid if angle between sun direction and magnetic field direction - is sufficiently large */ + double sinAngle = 0; + sinAngle = sin(acos(cos(cosAngleSunMag))); - double sinAngle = 0; - sinAngle = sin(acos(cos(cosAngleSunMag))); + if (!(sinAngle > sin(safeModeControllerParameters->sunMagAngleMin * M_PI / 180))) { + return; + } - if ( !(sinAngle > sin( safeModeControllerParameters->sunMagAngleMin * M_PI / 180))) { - return; - } + // Rate for Torque Calculation + double diffRate[3] = {0, 0, 0}; /* ADD TO MONITORING */ + VectorOperations::subtract(estSatRate, satRateRef, diffRate, 3); -// Rate for Torque Calculation - double diffRate[3] = {0, 0, 0}; /* ADD TO MONITORING */ - VectorOperations::subtract(estSatRate, satRateRef, diffRate, 3); + // Torque Align calculation + double kRateNoMekf = 0, kAlignNoMekf = 0; + kRateNoMekf = safeModeControllerParameters->k_rate_no_mekf; + kAlignNoMekf = safeModeControllerParameters->k_align_no_mekf; -// Torque Align calculation - double kRateNoMekf = 0, kAlignNoMekf = 0; - kRateNoMekf = safeModeControllerParameters->k_rate_no_mekf; - kAlignNoMekf = safeModeControllerParameters->k_align_no_mekf; + double cosAngleAlignErr = VectorOperations::dot(sunDirRef, susDirB); + double crossSusSunRef[3] = {0, 0, 0}; + VectorOperations::cross(sunDirRef, susDirB, crossSusSunRef); + double sinAngleAlignErr = VectorOperations::norm(crossSusSunRef, 3); - double cosAngleAlignErr = VectorOperations::dot(sunDirRef, susDirB); - double crossSusSunRef[3] = {0, 0, 0}; - VectorOperations::cross(sunDirRef, susDirB, crossSusSunRef); - double sinAngleAlignErr = VectorOperations::norm(crossSusSunRef, 3); + double torqueAlign[3] = {0, 0, 0}; + double angleAlignErr = acos(cosAngleAlignErr); + double torqueAlignFactor = kAlignNoMekf * angleAlignErr / sinAngleAlignErr; + VectorOperations::mulScalar(crossSusSunRef, torqueAlignFactor, torqueAlign, 3); - double torqueAlign[3] = {0, 0, 0}; - double angleAlignErr = acos(cosAngleAlignErr); - double torqueAlignFactor = kAlignNoMekf * angleAlignErr / sinAngleAlignErr; - VectorOperations::mulScalar(crossSusSunRef, torqueAlignFactor, torqueAlign, 3); + // Torque Rate Calculations + double torqueRate[3] = {0, 0, 0}; + VectorOperations::mulScalar(diffRate, -kRateNoMekf, torqueRate, 3); -//Torque Rate Calculations - double torqueRate[3] = {0, 0, 0}; - VectorOperations::mulScalar(diffRate, -kRateNoMekf, torqueRate, 3); + // 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); -//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); + // Magnetic moment + double magMomB[3] = {0, 0, 0}; + double crossMagFieldTorque[3] = {0, 0, 0}; + VectorOperations::cross(magFieldB, torqueB, crossMagFieldTorque); + double magMomFactor = pow(VectorOperations::norm(magFieldB, 3), 2); + VectorOperations::mulScalar(crossMagFieldTorque, 1 / magMomFactor, magMomB, 3); -//Magnetic moment - double magMomB[3] = {0, 0, 0}; - double crossMagFieldTorque[3] = {0, 0, 0}; - VectorOperations::cross(magFieldB, torqueB, crossMagFieldTorque); - double magMomFactor = pow( VectorOperations::norm(magFieldB, 3), 2 ); - VectorOperations::mulScalar(crossMagFieldTorque, 1/magMomFactor, magMomB, 3); - - outputMagMomB[0] = magMomB[0]; - outputMagMomB[1] = magMomB[1]; - outputMagMomB[2] = magMomB[2]; - - *outputValid = true; + outputMagMomB[0] = magMomB[0]; + outputMagMomB[1] = magMomB[1]; + outputMagMomB[2] = magMomB[2]; + *outputValid = true; } - - diff --git a/mission/controller/acs/control/SafeCtrl.h b/mission/controller/acs/control/SafeCtrl.h index c6d47324..70426c9f 100644 --- a/mission/controller/acs/control/SafeCtrl.h +++ b/mission/controller/acs/control/SafeCtrl.h @@ -8,57 +8,46 @@ #ifndef SAFECTRL_H_ #define SAFECTRL_H_ -#include "../SensorValues.h" -#include "../OutputValues.h" -#include "../AcsParameters.h" -#include "../config/classIds.h" -#include #include +#include #include -#include +#include "../AcsParameters.h" +#include "../OutputValues.h" +#include "../SensorValues.h" +#include "../config/classIds.h" -class SafeCtrl{ +class SafeCtrl { + public: + SafeCtrl(AcsParameters *acsParameters_); + virtual ~SafeCtrl(); -public: + static const uint8_t INTERFACE_ID = CLASS_ID::SAFE; + static const ReturnValue_t SAFECTRL_MEKF_INPUT_INVALID = MAKE_RETURN_CODE(0x01); - SafeCtrl(AcsParameters *acsParameters_); - virtual ~SafeCtrl(); + void loadAcsParameters(AcsParameters *acsParameters_); - static const uint8_t INTERFACE_ID = CLASS_ID::SAFE; - static const ReturnValue_t SAFECTRL_MEKF_INPUT_INVALID = MAKE_RETURN_CODE(0x01); + ReturnValue_t safeMekf(timeval now, double *quatBJ, bool *quatBJValid, double *magFieldModel, + bool *magFieldModelValid, double *sunDirModel, bool *sunDirModelValid, + double *satRateMekf, bool *rateMekfValid, double *sunDirRef, + double *satRatRef, // From Guidance (!) + double *outputMagMomB, bool *outputValid); - void loadAcsParameters(AcsParameters *acsParameters_); + void safeNoMekf(timeval now, double *susDirB, bool *susDirBValid, double *sunRateB, + bool *sunRateBValid, double *magFieldB, bool *magFieldBValid, double *magRateB, + bool *magRateBValid, double *sunDirRef, double *satRateRef, double *outputMagMomB, + bool *outputValid); - ReturnValue_t safeMekf(timeval now, double *quatBJ, bool *quatBJValid, - double *magFieldModel, bool *magFieldModelValid, - double *sunDirModel, bool *sunDirModelValid, - double *satRateMekf, bool *rateMekfValid, - double *sunDirRef, double *satRatRef, // From Guidance (!) - double *outputMagMomB, bool *outputValid); + void idleSunPointing(); // with reaction wheels - void safeNoMekf(timeval now, double *susDirB, bool *susDirBValid, - double *sunRateB, bool *sunRateBValid, - double *magFieldB, bool *magFieldBValid, - double *magRateB, bool *magRateBValid, - double *sunDirRef, double *satRateRef, - double *outputMagMomB, bool *outputValid); - - void idleSunPointing(); // with reaction wheels - -protected: - -private: - AcsParameters::SafeModeControllerParameters* safeModeControllerParameters; - AcsParameters::InertiaEIVE* inertiaEIVE; - double gainMatrixInertia[3][3]; - - double magFieldBState[3]; - timeval magFieldBStateTime; + protected: + private: + AcsParameters::SafeModeControllerParameters *safeModeControllerParameters; + AcsParameters::InertiaEIVE *inertiaEIVE; + double gainMatrixInertia[3][3]; + double magFieldBState[3]; + timeval magFieldBStateTime; }; - - #endif /* ACS_CONTROL_SAFECTRL_H_ */ - -- 2.34.1 From 06941fcf5b0dfcaaa545c42c1f766108f304b696 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 20 Oct 2022 11:08:21 +0200 Subject: [PATCH 070/101] fixed int32_t to double warnings --- mission/controller/acs/ActuatorCmd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index 920989ed..0dba2016 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -45,7 +45,7 @@ void ActuatorCmd::cmdSpeedToRws(const int32_t *speedRw0, const int32_t *speedRw1 } // Calculating the commanded speed in RPM for every reaction wheel - double speedRws[4] = {*speedRw0, *speedRw1, *speedRw2, *speedRw3}; + double speedRws[4] = {(double)*speedRw0, (double)*speedRw1, (double)*speedRw2, (double)*speedRw3}; double deltaSpeed[4] = {0, 0, 0, 0}; double commandTime = acsParameters.onBoardParams.sampleTime, inertiaWheel = acsParameters.rwHandlingParameters.inertiaWheel; -- 2.34.1 From 62bf792888d937a49c934041398a36a1945f143d Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 20 Oct 2022 11:09:02 +0200 Subject: [PATCH 071/101] removed comment --- mission/controller/acs/SensorProcessing.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index a6571496..8c89dda4 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -107,9 +107,6 @@ bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const for (uint8_t i = 0; i < 3; i++) { magFieldEst[i] = sensorFusionNumerator[i] / sensorFusionDenominator[i]; } - sif::debug << "magFeildEst: " << magFieldEst[0] << " , " << magFieldEst[1] << " , " - << magFieldEst[2] << std::endl; - ; validMagField = true; //-----------------------Mag Rate Computation --------------------------------------------------- -- 2.34.1 From 0d3509b99164d4277ebfdea6a2f2a0d62c476f82 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 20 Oct 2022 11:09:52 +0200 Subject: [PATCH 072/101] added actuator command values DataSet --- .../AcsCtrlDefinitions.h | 33 ++++++++++++++----- 1 file changed, 25 insertions(+), 8 deletions(-) diff --git a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h index c122be43..4a608f71 100644 --- a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h +++ b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h @@ -16,7 +16,8 @@ enum SetIds : uint32_t { GYR_SENSOR_DATA, GYR_PROCESSED_DATA, GPS_SENSOR_DATA, - MEKF_DATA + MEKF_DATA, + ACTUATOR_CMD_DATA }; enum PoolIds : lp_id_t { @@ -81,22 +82,27 @@ enum PoolIds : lp_id_t { GYR_2_VEC, GYR_3_VEC, GYR_VEC_TOT, - // GPS PROCESSED + // GPS Processed GC_LATITUDE, GD_LONGITUDE, // MEKF SAT_ROT_RATE_MEKF, QUAT_MEKF, + // Actuator Cmd + RW_TARGET_TORQUE, + RW_TARGET_SPEED, + MTQ_TARGET_DIPOLE, }; static constexpr uint8_t MGM_SET_RAW_ENTRIES = 10; -static constexpr uint8_t MGM_SET_PROCESSED_ENTRIES = 7 * sizeof(float) + 1 * sizeof(double); +static constexpr uint8_t MGM_SET_PROCESSED_ENTRIES = 8; static constexpr uint8_t SUS_SET_RAW_ENTRIES = 12; -static constexpr uint8_t SUS_SET_PROCESSED_ENTRIES = 14 * sizeof(float) + 1 * sizeof(double); -static constexpr uint8_t GYR_SET_RAW_ENTRIES = 2 * sizeof(float) + 2 * sizeof(double); -static constexpr uint8_t GYR_SET_PROCESSED_ENTRIES = 5 * sizeof(double); -static constexpr uint8_t GPS_SET_PROCESSED_ENTRIES = 2 * sizeof(double); -static constexpr uint8_t MEKF_SET_ENTRIES = 14 * sizeof(float) + 1 * sizeof(double); +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 = 2; +static constexpr uint8_t MEKF_SET_ENTRIES = 2; +static constexpr uint8_t ACT_CMD_SET_ENTRIES = 3; /** * @brief Raw MGM sensor data. Includes the IMTQ sensor data and actuator status. @@ -227,6 +233,17 @@ class MekfData : public StaticLocalDataSet { private: }; +class ActuatorCmdData : public StaticLocalDataSet { + public: + ActuatorCmdData(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, ACTUATOR_CMD_DATA) {} + + lp_vec_t rwTargetTorque = lp_vec_t(sid.objectId, RW_TARGET_TORQUE, this); + lp_vec_t rwTargetSpeed = lp_vec_t(sid.objectId, RW_TARGET_SPEED, this); + lp_vec_t mtqTargetDipole = lp_vec_t(sid.objectId, MTQ_TARGET_DIPOLE, this); + + private: +}; + } // namespace acsctrl #endif /* MISSION_CONTROLLER_CONTROLLERDEFINITIONS_ACSCTRLDEFINITIONS_H_ */ -- 2.34.1 From 8b23fd3dd261d64090fc5c22c7963f880bc73d1a Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 24 Oct 2022 10:29:57 +0200 Subject: [PATCH 073/101] fixed int32_t to double warnings. reformats --- .../acs/MultiplicativeKalmanFilter.cpp | 2274 ++++++++--------- .../acs/MultiplicativeKalmanFilter.h | 148 +- mission/controller/acs/Navigation.cpp | 8 +- mission/controller/acs/control/PtgCtrl.cpp | 4 +- 4 files changed, 1186 insertions(+), 1248 deletions(-) diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.cpp b/mission/controller/acs/MultiplicativeKalmanFilter.cpp index 5f7facd2..8cfa0ad3 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.cpp +++ b/mission/controller/acs/MultiplicativeKalmanFilter.cpp @@ -6,1199 +6,1143 @@ */ #include "MultiplicativeKalmanFilter.h" -#include "util/CholeskyDecomposition.h" -#include "util/MathOperations.h" -#include -#include + #include #include #include +#include +#include + +#include "util/CholeskyDecomposition.h" +#include "util/MathOperations.h" /*Initialisation of values for parameters in constructor*/ -MultiplicativeKalmanFilter::MultiplicativeKalmanFilter(AcsParameters *acsParameters_) : - initialQuaternion { 0.5, 0.5, 0.5, 0.5 },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(AcsParameters *acsParameters_) + : initialQuaternion{0.5, 0.5, 0.5, 0.5}, + 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); /*Sensor noises also here*/ } -void MultiplicativeKalmanFilter::loadAcsParameters( - AcsParameters *acsParameters_) { - inertiaEIVE = &(acsParameters_->inertiaEIVE); - kalmanFilterParameters = &(acsParameters_->kalmanFilterParameters); /*Sensor noises also here*/ -} +void MultiplicativeKalmanFilter::reset() {} -void MultiplicativeKalmanFilter::reset() { +void 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) { // valids for "model measurements"? + // check for valid mag/sun + if (*validMagField_ && *validSS && *validSSModel && *validMagModel) { + validInit = true; + // AcsParameters mekfEstParams; + // loadAcsParameters(&mekfEstParams); + // QUEST ALGO ----------------------------------------------------------------------- + double sigmaSun = 0, sigmaMag = 0, sigmaGyro = 0; + sigmaSun = kalmanFilterParameters->sensorNoiseSS; + sigmaMag = kalmanFilterParameters->sensorNoiseMAG; -} + sigmaGyro = 0.1 * 3.141 / 180; // acs parameters -void 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) { // valids for "model measurements"? - // check for valid mag/sun - if (*validMagField_ && *validSS && *validSSModel && *validMagModel) { - validInit = true; - //AcsParameters mekfEstParams; - //loadAcsParameters(&mekfEstParams); - // QUEST ALGO ----------------------------------------------------------------------- - double sigmaSun = 0, sigmaMag = 0, sigmaGyro = 0; - sigmaSun = kalmanFilterParameters->sensorNoiseSS; - sigmaMag = kalmanFilterParameters->sensorNoiseMAG; + double normMagB[3] = {0, 0, 0}, normSunB[3] = {0, 0, 0}, normMagJ[3] = {0, 0, 0}, + normSunJ[3] = {0, 0, 0}; + VectorOperations::normalize(magneticField_, normMagB, 3); // b2 + VectorOperations::normalize(sunDir_, normSunB, 3); // b1 + VectorOperations::normalize(magFieldJ, normMagJ, 3); // r2 + VectorOperations::normalize(sunDirJ, normSunJ, 3); // r1 - sigmaGyro = 0.1*3.141/180; // acs parameters + double thirdAxis_B[3] = {0, 0, 0}, thirdAxis_J[3] = {0, 0, 0}; + VectorOperations::cross(normSunJ, normMagJ, thirdAxis_J); + VectorOperations::cross(normSunB, normMagB, thirdAxis_B); + VectorOperations::normalize(thirdAxis_J, thirdAxis_J, 3); // rx + VectorOperations::normalize(thirdAxis_B, thirdAxis_B, 3); // bx - double normMagB[3] = {0,0,0}, normSunB[3] = {0,0,0}, - normMagJ[3] = {0,0,0}, normSunJ[3] = {0,0,0}; - VectorOperations::normalize(magneticField_, normMagB, 3); // b2 - VectorOperations::normalize(sunDir_, normSunB, 3); //b1 - VectorOperations::normalize(magFieldJ, normMagJ, 3); //r2 - VectorOperations::normalize(sunDirJ, normSunJ, 3); //r1 + double weigthSun = 1 / (sigmaSun * sigmaSun); // a1 + double weigthMag = 1 / (sigmaMag * sigmaMag); // a2 - double thirdAxis_B[3] = {0,0,0}, thirdAxis_J[3] = {0,0,0}; - VectorOperations::cross(normSunJ, normMagJ, thirdAxis_J); - VectorOperations::cross(normSunB, normMagB, thirdAxis_B); - VectorOperations::normalize(thirdAxis_J, thirdAxis_J, 3); //rx - VectorOperations::normalize(thirdAxis_B, thirdAxis_B, 3); //bx + double a[3] = {0, 0, 0}, b[3] = {0, 0, 0}; + VectorOperations::mulScalar(normSunB, weigthSun, a, 3); // a + VectorOperations::mulScalar(normMagB, weigthMag, b, 3); // b - double weigthSun= 1 / (sigmaSun * sigmaSun); //a1 - double weigthMag= 1 / (sigmaMag * sigmaMag); //a2 + double thirdAxisCross[3] = {0, 0, 0}, weightACross[3] = {0, 0, 0}, weightBCross[3] = {0, 0, 0}, + weigthCrossSum[3] = {0, 0, 0}; + VectorOperations::cross(thirdAxis_B, thirdAxis_J, + thirdAxisCross); // cross(bx,rx) + VectorOperations::cross(a, normSunJ, weightACross); + VectorOperations::cross(b, normMagJ, weightBCross); + VectorOperations::add(weightACross, weightBCross, weigthCrossSum); - double a[3] = {0,0,0}, b[3] = {0,0,0}; - VectorOperations::mulScalar(normSunB, weigthSun, a, 3); //a - VectorOperations::mulScalar(normMagB, weigthMag, b, 3); //b + double thirdAxisSum[3] = {0, 0, 0}, sum2[3] = {0, 0, 0}; + VectorOperations::add(thirdAxis_B, thirdAxis_J, thirdAxisSum); + VectorOperations::add(weightACross, weightBCross, sum2); - double thirdAxisCross[3] = {0,0,0}, weightACross[3] = {0,0,0}, - weightBCross[3] = {0,0,0},weigthCrossSum[3] = {0,0,0}; - VectorOperations::cross(thirdAxis_B, thirdAxis_J, - thirdAxisCross); //cross(bx,rx) - VectorOperations::cross(a, normSunJ, weightACross); - VectorOperations::cross(b, normMagJ, weightBCross); - VectorOperations::add(weightACross, weightBCross, - weigthCrossSum); + double alpha = 0, beta = 0, gamma = 0, constPlus = 0, constMin = 0; + alpha = (1 + VectorOperations::dot(thirdAxis_B, thirdAxis_J)) * + (VectorOperations::dot(a, normSunJ) + + VectorOperations::dot(b, normMagJ)) + + VectorOperations::dot(thirdAxisCross, weigthCrossSum); + beta = VectorOperations::dot(thirdAxisSum, sum2); + gamma = sqrt(alpha * alpha + beta * beta); + constPlus = 1 / (2 * sqrt(gamma * (gamma + alpha) * + (1 + VectorOperations::dot(thirdAxis_B, thirdAxis_J)))); + constMin = 1 / (2 * sqrt(gamma * (gamma - alpha) * + (1 + VectorOperations::dot(thirdAxis_B, thirdAxis_J)))); - double thirdAxisSum[3] = {0,0,0}, sum2[3] = {0,0,0}; - VectorOperations::add(thirdAxis_B, thirdAxis_J, thirdAxisSum); - VectorOperations::add(weightACross, weightBCross, sum2); + /*Quaternion Computation*/ + double quat[3] = {0, 0, 0}, var1[3] = {0, 0, 0}, var2[3] = {0, 0, 0}; + if (alpha >= 0) { + VectorOperations::mulScalar(thirdAxisCross, gamma + alpha, var1, 3); + VectorOperations::add(thirdAxis_B, thirdAxis_J, var2, 3); + VectorOperations::mulScalar(var2, beta, var2, 3); + VectorOperations::add(var1, var2, quat); - double alpha = 0, beta = 0, gamma = 0, constPlus = 0, constMin = 0; - alpha = (1 + VectorOperations::dot(thirdAxis_B, thirdAxis_J)) - * (VectorOperations::dot(a, normSunJ) - + VectorOperations::dot(b, normMagJ)) - + VectorOperations::dot(thirdAxisCross, weigthCrossSum); - beta = VectorOperations::dot(thirdAxisSum, sum2); - gamma = sqrt(alpha * alpha + beta * beta); - constPlus = 1 - / (2 - * sqrt( - gamma * (gamma + alpha) - * (1 - + VectorOperations::dot( - thirdAxis_B, - thirdAxis_J)))); - constMin = 1 - / (2 - * sqrt( - gamma * (gamma - alpha) - * (1 - + VectorOperations::dot( - thirdAxis_B, - thirdAxis_J)))); + for (int i = 0; i < 3; i++) { + initialQuaternion[i] = quat[i]; + } + initialQuaternion[3] = + (gamma + alpha) * (1 + VectorOperations::dot(thirdAxis_B, thirdAxis_J)); + VectorOperations::mulScalar(initialQuaternion, constPlus, initialQuaternion, 4); + } else { + double diffGammaAlpha = gamma - alpha; + VectorOperations::mulScalar(thirdAxisCross, beta, var1, 3); + VectorOperations::add(thirdAxis_B, thirdAxis_J, var2, 3); + VectorOperations::mulScalar(var2, diffGammaAlpha, var2, 3); + VectorOperations::add(var1, var2, quat); + for (int i = 0; i < 3; i++) { + initialQuaternion[i] = quat[i]; + } + initialQuaternion[3] = beta * (1 + VectorOperations::dot(thirdAxis_B, thirdAxis_J)); + VectorOperations::mulScalar(initialQuaternion, constMin, initialQuaternion, 4); + } + propagatedQuaternion[0] = initialQuaternion[0]; + propagatedQuaternion[1] = initialQuaternion[1]; + propagatedQuaternion[2] = initialQuaternion[2]; + propagatedQuaternion[3] = initialQuaternion[3]; - /*Quaternion Computation*/ - double quat[3] = {0,0,0}, var1[3] = {0,0,0}, var2[3] = {0,0,0}; - if (alpha >= 0) { - VectorOperations::mulScalar(thirdAxisCross, gamma + alpha, - var1, 3); - VectorOperations::add(thirdAxis_B, thirdAxis_J, var2, 3); - VectorOperations::mulScalar(var2, beta, var2, 3); - VectorOperations::add(var1, var2, quat); + /*Initial Covariance Matrix------------------------------------ */ + double dcmBJ[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, sunEstB[3] = {0, 0, 0}, + magEstB[3] = {0, 0, 0}; + QuaternionOperations::toDcm(initialQuaternion, dcmBJ); + MatrixOperations::multiply(*dcmBJ, normSunJ, sunEstB, 3, 3, 1); + MatrixOperations::multiply(*dcmBJ, normMagJ, magEstB, 3, 3, 1); - for (int i = 0; i < 3; i++) { - initialQuaternion[i] = quat[i]; - } - initialQuaternion[3] = (gamma + alpha) - * (1 - + VectorOperations::dot(thirdAxis_B, - thirdAxis_J)); - VectorOperations::mulScalar(initialQuaternion, - constPlus, initialQuaternion, 4); - } else { - double diffGammaAlpha = gamma - alpha; - VectorOperations::mulScalar(thirdAxisCross, beta, var1, 3); - VectorOperations::add(thirdAxis_B, thirdAxis_J, var2, 3); - VectorOperations::mulScalar(var2, diffGammaAlpha, var2, 3); - VectorOperations::add(var1, var2, quat); - for (int i = 0; i < 3; i++) { - initialQuaternion[i] = quat[i]; - } - initialQuaternion[3] = beta - * (1 - + VectorOperations::dot(thirdAxis_B, - thirdAxis_J)); - VectorOperations::mulScalar(initialQuaternion, - constMin, initialQuaternion, 4); + double matrixSun[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, + matrixMag[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, + matrixSunMag[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, + matrixMagSun[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + /* vector*transpose(vector)*/ + MatrixOperations::multiply(sunEstB, sunEstB, *matrixSun, 3, 1, 3); + MatrixOperations::multiply(magEstB, magEstB, *matrixMag, 3, 1, 3); + MatrixOperations::multiply(sunEstB, magEstB, *matrixSunMag, 3, 1, 3); + MatrixOperations::multiply(magEstB, sunEstB, *matrixMagSun, 3, 1, 3); - } - propagatedQuaternion[0] = initialQuaternion[0]; - propagatedQuaternion[1] = initialQuaternion[1]; - propagatedQuaternion[2] = initialQuaternion[2]; - propagatedQuaternion[3] = initialQuaternion[3]; + double partA[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, partB = 0; + MatrixOperations::multiplyScalar(*matrixSun, weigthSun * weigthSun, *matrixSun, 3, 3); + MatrixOperations::multiplyScalar(*matrixMag, weigthMag * weigthMag, *matrixMag, 3, 3); + MatrixOperations::add(*matrixSunMag, *matrixMagSun, *partA, 3, 3); + double factor = weigthMag * weigthSun * VectorOperations::dot(sunEstB, magEstB); + MatrixOperations::multiplyScalar(*partA, factor, *partA, 3, 3); + MatrixOperations::add(*partA, *matrixSun, *partA, 3, 3); + MatrixOperations::add(*partA, *matrixMag, *partA, 3, 3); - /*Initial Covariance Matrix------------------------------------ */ - double dcmBJ[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, - sunEstB[3] = {0,0,0}, magEstB[3] = {0,0,0}; - QuaternionOperations::toDcm(initialQuaternion, dcmBJ); - MatrixOperations::multiply(*dcmBJ, normSunJ, sunEstB, 3, 3, 1); - MatrixOperations::multiply(*dcmBJ, normMagJ, magEstB, 3, 3, - 1); + double crossSunMag[3] = {0, 0, 0}; + double identityMatrix3[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}}; + VectorOperations::cross(sunEstB, magEstB, crossSunMag); + partB = 1 / (weigthMag * weigthSun * pow(VectorOperations::norm(crossSunMag, 3), 2)); + MatrixOperations::multiplyScalar(*partA, partB, *partA, 3, 3); + MatrixOperations::add(*matrixSunMag, *identityMatrix3, *partA, 3, 3); + factor = 1 / (weigthMag + weigthMag); - double matrixSun[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, - matrixMag[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, - matrixSunMag[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, - matrixMagSun[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; - /* vector*transpose(vector)*/ - MatrixOperations::multiply(sunEstB, sunEstB, *matrixSun, 3, 1, 3); - MatrixOperations::multiply(magEstB, magEstB, *matrixMag, 3, 1, 3); - MatrixOperations::multiply(sunEstB, magEstB, *matrixSunMag, 3, 1, 3); - MatrixOperations::multiply(magEstB, sunEstB, *matrixMagSun, 3, 1, 3); - - double partA[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, partB = 0; - MatrixOperations::multiplyScalar(*matrixSun, - weigthSun * weigthSun, *matrixSun, 3, 3); - MatrixOperations::multiplyScalar(*matrixMag, - weigthMag * weigthMag, *matrixMag, 3, 3); - MatrixOperations::add(*matrixSunMag, *matrixMagSun, *partA, 3, - 3); - double factor = weigthMag * weigthSun - * VectorOperations::dot(sunEstB, magEstB); - MatrixOperations::multiplyScalar(*partA, factor, *partA, 3, 3); - MatrixOperations::add(*partA, *matrixSun, *partA, 3, 3); - MatrixOperations::add(*partA, *matrixMag, *partA, 3, 3); - - double crossSunMag[3] = {0,0,0}; - double identityMatrix3[3][3] = { { 1, 0, 0 }, { 0, 1, 0 }, { 0, 0, 1 } }; - VectorOperations::cross(sunEstB, magEstB, crossSunMag); - partB = - 1 - / (weigthMag * weigthSun - * pow( - VectorOperations::norm( - crossSunMag, 3), 2)); - MatrixOperations::multiplyScalar(*partA, partB, *partA, 3, 3); - MatrixOperations::add(*matrixSunMag, *identityMatrix3, *partA, 3, - 3); - factor = 1 / (weigthMag + weigthMag); - - double questCovMatrix[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; - MatrixOperations::multiplyScalar(*partA, factor, - *questCovMatrix, 3, 3); - double initGyroCov[3][3] = {{pow(sigmaGyro,2),0,0},{0,pow(sigmaGyro,2),0}, - {0,0,pow(sigmaGyro,2)}}; - initialCovarianceMatrix[0][0] = questCovMatrix[0][0]; - initialCovarianceMatrix[0][1] = questCovMatrix[0][1]; - initialCovarianceMatrix[0][2] = questCovMatrix[0][2]; - initialCovarianceMatrix[0][3] = 0; - initialCovarianceMatrix[0][4] = 0; - initialCovarianceMatrix[0][5] = 0; - initialCovarianceMatrix[1][0] = questCovMatrix[1][0]; - initialCovarianceMatrix[1][1] = questCovMatrix[1][1]; - initialCovarianceMatrix[1][2] = questCovMatrix[1][2]; - initialCovarianceMatrix[1][3] = 0; - initialCovarianceMatrix[1][4] = 0; - initialCovarianceMatrix[1][5] = 0; - initialCovarianceMatrix[2][0] = questCovMatrix[2][0]; - initialCovarianceMatrix[2][1] = questCovMatrix[2][1]; - initialCovarianceMatrix[2][2] = questCovMatrix[2][2]; - initialCovarianceMatrix[2][3] = 0; - initialCovarianceMatrix[2][4] = 0; - initialCovarianceMatrix[2][5] = 0; - initialCovarianceMatrix[3][0] = 0; - initialCovarianceMatrix[3][1] = 0; - initialCovarianceMatrix[3][2] = 0; - initialCovarianceMatrix[3][3] = initGyroCov[0][0]; - initialCovarianceMatrix[3][4] = initGyroCov[0][1]; - initialCovarianceMatrix[3][5] = initGyroCov[0][2]; - initialCovarianceMatrix[4][0] = 0; - initialCovarianceMatrix[4][1] = 0; - initialCovarianceMatrix[4][2] = 0; - initialCovarianceMatrix[4][3] = initGyroCov[1][0]; - initialCovarianceMatrix[4][4] = initGyroCov[1][1]; - initialCovarianceMatrix[4][5] = initGyroCov[1][2]; - initialCovarianceMatrix[5][0] = 0; - initialCovarianceMatrix[5][1] = 0; - initialCovarianceMatrix[5][2] = 0; - initialCovarianceMatrix[5][3] = initGyroCov[2][0]; - initialCovarianceMatrix[5][4] = initGyroCov[2][1]; - initialCovarianceMatrix[5][5] = initGyroCov[2][2]; - //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}}; - } else { - // no initialisation possible, no valid measurements - validInit = false; - } + double questCovMatrix[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MatrixOperations::multiplyScalar(*partA, factor, *questCovMatrix, 3, 3); + double initGyroCov[3][3] = { + {pow(sigmaGyro, 2), 0, 0}, {0, pow(sigmaGyro, 2), 0}, {0, 0, pow(sigmaGyro, 2)}}; + initialCovarianceMatrix[0][0] = questCovMatrix[0][0]; + initialCovarianceMatrix[0][1] = questCovMatrix[0][1]; + initialCovarianceMatrix[0][2] = questCovMatrix[0][2]; + initialCovarianceMatrix[0][3] = 0; + initialCovarianceMatrix[0][4] = 0; + initialCovarianceMatrix[0][5] = 0; + initialCovarianceMatrix[1][0] = questCovMatrix[1][0]; + initialCovarianceMatrix[1][1] = questCovMatrix[1][1]; + initialCovarianceMatrix[1][2] = questCovMatrix[1][2]; + initialCovarianceMatrix[1][3] = 0; + initialCovarianceMatrix[1][4] = 0; + initialCovarianceMatrix[1][5] = 0; + initialCovarianceMatrix[2][0] = questCovMatrix[2][0]; + initialCovarianceMatrix[2][1] = questCovMatrix[2][1]; + initialCovarianceMatrix[2][2] = questCovMatrix[2][2]; + initialCovarianceMatrix[2][3] = 0; + initialCovarianceMatrix[2][4] = 0; + initialCovarianceMatrix[2][5] = 0; + initialCovarianceMatrix[3][0] = 0; + initialCovarianceMatrix[3][1] = 0; + initialCovarianceMatrix[3][2] = 0; + initialCovarianceMatrix[3][3] = initGyroCov[0][0]; + initialCovarianceMatrix[3][4] = initGyroCov[0][1]; + initialCovarianceMatrix[3][5] = initGyroCov[0][2]; + initialCovarianceMatrix[4][0] = 0; + initialCovarianceMatrix[4][1] = 0; + initialCovarianceMatrix[4][2] = 0; + initialCovarianceMatrix[4][3] = initGyroCov[1][0]; + initialCovarianceMatrix[4][4] = initGyroCov[1][1]; + initialCovarianceMatrix[4][5] = initGyroCov[1][2]; + initialCovarianceMatrix[5][0] = 0; + initialCovarianceMatrix[5][1] = 0; + initialCovarianceMatrix[5][2] = 0; + initialCovarianceMatrix[5][3] = initGyroCov[2][0]; + initialCovarianceMatrix[5][4] = initGyroCov[2][1]; + initialCovarianceMatrix[5][5] = initGyroCov[2][2]; + // 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}}; + } else { + // no initialisation possible, no valid measurements + validInit = false; + } } // --------------- MEKF DISCRETE TIME STEP ------------------------------- ReturnValue_t MultiplicativeKalmanFilter::mekfEst( - const double *quaternionSTR, const bool *validSTR_, - const double *rateRMUs_, const bool *validRMUs_, - 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 *outputQuat, double *outputSatRate) { - - // Check for RMU Measurements - //AcsParameters mekfEstParams; - //loadAcsParameters(&mekfEstParams); - int MDF = 0; // Matrix Dimension Factor - if (!(*validRMUs_)){ - validMekf = false; - return KALMAN_NO_RMU_MEAS; - } - // Check for Model Calculations - else if (!(*validSSModel) || !(*validMagModel)){ - validMekf = false; - return KALMAN_NO_MODEL; - } - // Check Measurements available from SS, MAG, STR - if (*validSS && *validMagField_ && *validSTR_){ - sensorsAvail = 1; - MDF = 9; - } - else if (*validSS && *validMagField_ && !(*validSTR_)){ - sensorsAvail = 2; - MDF = 6; - } - else if (*validSS && !(*validMagField_) && *validSTR_){ - sensorsAvail = 3; - MDF = 6; - } - else if (!(*validSS) && *validMagField_ && *validSTR_){ - sensorsAvail = 4; - MDF = 6; - } - else if (*validSS && !(*validMagField_) && !(*validSTR_)){ - sensorsAvail = 5; - MDF = 3; - } - else if (!(*validSS) && *validMagField_ && !(*validSTR_)){ - sensorsAvail = 6; - MDF = 3; - } - else if (!(*validSS) && !(*validMagField_) && *validSTR_){ - sensorsAvail = 7; - MDF = 3; - } - else{ - sensorsAvail = 8; //no measurements - validMekf = false; - return returnvalue::FAILED; - } - - // If we are here, MEKF will perform - double sigmaSun = 0, sigmaMag = 0, sigmaStr = 0; - sigmaSun = kalmanFilterParameters->sensorNoiseSS; - sigmaMag = kalmanFilterParameters->sensorNoiseMAG; - sigmaStr = kalmanFilterParameters->sensorNoiseSTR; - - double normMagB[3] = {0,0,0}, normSunB[3] = {0,0,0}, - normMagJ[3] = {0,0,0}, normSunJ[3] = {0,0,0}; - VectorOperations::normalize(magneticField_, normMagB, 3); // b2 - VectorOperations::normalize(sunDir_, normSunB, 3); //b1 - VectorOperations::normalize(magFieldJ, normMagJ, 3); //r2 - VectorOperations::normalize(sunDirJ, normSunJ, 3); //r1 - - /*-------GAIN - UPDATE - STEP------*/ - double covMatrix11[3][3] = {{pow(sigmaSun,2),0,0},{0,pow(sigmaSun,2),0},{0,0,pow(sigmaSun,2)}}; - double covMatrix22[3][3] = {{pow(sigmaMag,2),0,0},{0,pow(sigmaMag,2),0},{0,0,pow(sigmaMag,2)}}; - double covMatrix33[3][3] = {{pow(sigmaStr,2),0,0},{0,pow(sigmaStr,2),0},{0,0,pow(sigmaStr,2)}}; - - double dcmBJ[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, - sunEstB[3] = {0,0,0}, magEstB[3] = {0,0,0}; - QuaternionOperations::toDcm(propagatedQuaternion, dcmBJ); - MatrixOperations::multiply(*dcmBJ, normSunJ, sunEstB, 3, 3, 1); - MatrixOperations::multiply(*dcmBJ, normMagJ, magEstB, 3, 3, - 1); - double quatEstErr[3] = {0,0,0}; - - //Measurement Sensitivity Matrix - double measSensMatrix11[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; // ss - double measSensMatrix22[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; // mag - double measSensMatrix33[3][3] = {{1,0,0},{0,1,0},{0,0,1}}; // str - MathOperations::skewMatrix(sunEstB, *measSensMatrix11); - MathOperations::skewMatrix(magEstB, *measSensMatrix22); - - double measVecQuat[3] = {0,0,0}; - if (*validSTR_){ - double quatError[4] = {0,0,0,0}; - double invPropagatedQuat[4] = {0,0,0,0}; - QuaternionOperations::inverse(propagatedQuaternion, invPropagatedQuat); - QuaternionOperations::multiply(quaternionSTR, invPropagatedQuat, quatError); - for (int i = 0 ; i < 3;i++){ - measVecQuat[i]=2*quatError[i]/quatError[3]; - } - } - // Adjust matrices based on valid measurements - double measSensMatrix[MDF][6], measCovMatrix[MDF][MDF], measVec[MDF], - measEstVec[MDF]; - if (sensorsAvail==1){ //All measurements valid - measSensMatrix[0][0] = measSensMatrix11[0][0]; - measSensMatrix[0][1] = measSensMatrix11[0][1]; - measSensMatrix[0][2] = measSensMatrix11[0][2]; - measSensMatrix[0][3] = 0; - measSensMatrix[0][4] = 0; - measSensMatrix[0][5] = 0; - measSensMatrix[1][0] = measSensMatrix11[1][0]; - measSensMatrix[1][1] = measSensMatrix11[1][1]; - measSensMatrix[1][2] = measSensMatrix11[1][2]; - measSensMatrix[1][3] = 0; - measSensMatrix[1][4] = 0; - measSensMatrix[1][5] = 0; - measSensMatrix[2][0] = measSensMatrix11[2][0]; - measSensMatrix[2][1] = measSensMatrix11[2][1]; - measSensMatrix[2][2] = measSensMatrix11[2][2]; - measSensMatrix[2][3] = 0; - measSensMatrix[2][4] = 0; - measSensMatrix[2][5] = 0; - measSensMatrix[3][0] = measSensMatrix22[0][0]; - measSensMatrix[3][1] = measSensMatrix22[0][1]; - measSensMatrix[3][2] = measSensMatrix22[0][2]; - measSensMatrix[3][3] = 0; - measSensMatrix[3][4] = 0; - measSensMatrix[3][5] = 0; - measSensMatrix[4][0] = measSensMatrix22[1][0]; - measSensMatrix[4][1] = measSensMatrix22[1][1]; - measSensMatrix[4][2] = measSensMatrix22[1][2]; - measSensMatrix[4][3] = 0; - measSensMatrix[4][4] = 0; - measSensMatrix[4][5] = 0; - measSensMatrix[5][0] = measSensMatrix22[2][0]; - measSensMatrix[5][1] = measSensMatrix22[2][1]; - measSensMatrix[5][2] = measSensMatrix22[2][2]; - measSensMatrix[5][3] = 0; - measSensMatrix[5][4] = 0; - measSensMatrix[5][5] = 0; - measSensMatrix[6][0] = measSensMatrix33[0][0]; - measSensMatrix[6][1] = measSensMatrix33[0][1]; - measSensMatrix[6][2] = measSensMatrix33[0][2]; - measSensMatrix[6][3] = 0; - measSensMatrix[6][4] = 0; - measSensMatrix[6][5] = 0; - measSensMatrix[7][0] = measSensMatrix33[1][0]; - measSensMatrix[7][1] = measSensMatrix33[1][1]; - measSensMatrix[7][2] = measSensMatrix33[1][2]; - measSensMatrix[7][3] = 0; - measSensMatrix[7][4] = 0; - measSensMatrix[7][5] = 0; - measSensMatrix[8][0] = measSensMatrix33[2][0]; - measSensMatrix[8][1] = measSensMatrix33[2][1]; - measSensMatrix[8][2] = measSensMatrix33[2][2]; - measSensMatrix[8][3] = 0; - measSensMatrix[8][4] = 0; - measSensMatrix[8][5] = 0; - - measCovMatrix[0][0] = covMatrix11[0][0]; - measCovMatrix[0][1] = covMatrix11[0][1]; - measCovMatrix[0][2] = covMatrix11[0][2]; - measCovMatrix[0][3] = 0; - measCovMatrix[0][4] = 0; - measCovMatrix[0][5] = 0; - measCovMatrix[0][6] = 0; - measCovMatrix[0][7] = 0; - measCovMatrix[0][8] = 0; - measCovMatrix[1][0] = covMatrix11[1][0]; - measCovMatrix[1][1] = covMatrix11[1][1]; - measCovMatrix[1][2] = covMatrix11[1][2]; - measCovMatrix[1][3] = 0; - measCovMatrix[1][4] = 0; - measCovMatrix[1][5] = 0; - measCovMatrix[1][6] = 0; - measCovMatrix[1][7] = 0; - measCovMatrix[1][8] = 0; - measCovMatrix[2][0] = covMatrix11[2][0]; - measCovMatrix[2][1] = covMatrix11[2][1]; - measCovMatrix[2][2] = covMatrix11[2][2]; - measCovMatrix[2][3] = 0; - measCovMatrix[2][4] = 0; - measCovMatrix[2][5] = 0; - measCovMatrix[2][6] = 0; - measCovMatrix[2][7] = 0; - measCovMatrix[2][8] = 0; - measCovMatrix[3][0] = 0; - measCovMatrix[3][1] = 0; - measCovMatrix[3][2] = 0; - measCovMatrix[3][3] = covMatrix22[0][0]; - measCovMatrix[3][4] = covMatrix22[0][1]; - measCovMatrix[3][5] = covMatrix22[0][2]; - measCovMatrix[3][6] = 0; - measCovMatrix[3][7] = 0; - measCovMatrix[3][8] = 0; - measCovMatrix[4][0] = 0; - measCovMatrix[4][1] = 0; - measCovMatrix[4][2] = 0; - measCovMatrix[4][3] = covMatrix22[1][0]; - measCovMatrix[4][4] = covMatrix22[1][1]; - measCovMatrix[4][5] = covMatrix22[1][2]; - measCovMatrix[4][6] = 0; - measCovMatrix[4][7] = 0; - measCovMatrix[4][8] = 0; - measCovMatrix[5][0] = 0; - measCovMatrix[5][1] = 0; - measCovMatrix[5][2] = 0; - measCovMatrix[5][3] = covMatrix22[2][0]; - measCovMatrix[5][4] = covMatrix22[2][1]; - measCovMatrix[5][5] = covMatrix22[2][2]; - measCovMatrix[5][6] = 0; - measCovMatrix[5][7] = 0; - measCovMatrix[5][8] = 0; - measCovMatrix[6][0] = 0; - measCovMatrix[6][1] = 0; - measCovMatrix[6][2] = 0; - measCovMatrix[6][3] = 0; - measCovMatrix[6][4] = 0; - measCovMatrix[6][5] = 0; - measCovMatrix[6][6] = covMatrix33[0][0]; - measCovMatrix[6][7] = covMatrix33[0][1]; - measCovMatrix[6][8] = covMatrix33[0][2]; - measCovMatrix[7][0] = 0; - measCovMatrix[7][1] = 0; - measCovMatrix[7][2] = 0; - measCovMatrix[7][3] = 0; - measCovMatrix[7][4] = 0; - measCovMatrix[7][5] = 0; - measCovMatrix[7][6] = covMatrix33[1][0]; - measCovMatrix[7][7] = covMatrix33[1][1]; - measCovMatrix[7][8] = covMatrix33[1][2]; - measCovMatrix[8][0] = 0; - measCovMatrix[8][1] = 0; - measCovMatrix[8][2] = 0; - measCovMatrix[8][3] = 0; - measCovMatrix[8][4] = 0; - measCovMatrix[8][5] = 0; - measCovMatrix[8][6] = covMatrix33[2][0]; - measCovMatrix[8][7] = covMatrix33[2][1]; - measCovMatrix[8][8] = covMatrix33[2][2]; - - measVec[0] = normSunB[0]; - measVec[1] = normSunB[1]; - measVec[2] = normSunB[2]; - measVec[3] = normMagB[0]; - measVec[4] = normMagB[1]; - measVec[5] = normMagB[2]; - measVec[6] = measVecQuat[0]; - measVec[7] = measVecQuat[1]; - measVec[8] = measVecQuat[2]; - - measEstVec[0] = sunEstB[0]; - measEstVec[1] = sunEstB[1]; - measEstVec[2] = sunEstB[2]; - measEstVec[3] = magEstB[0]; - measEstVec[4] = magEstB[1]; - measEstVec[5] = magEstB[2]; - measEstVec[6] = quatEstErr[0]; - measEstVec[7] = quatEstErr[1]; - measEstVec[8] = quatEstErr[2]; - - } - else if(sensorsAvail==2){ // ss / mag valid - measSensMatrix[0][0] = measSensMatrix11[0][0]; - measSensMatrix[0][1] = measSensMatrix11[0][1]; - measSensMatrix[0][2] = measSensMatrix11[0][2]; - measSensMatrix[0][3] = 0; - measSensMatrix[0][4] = 0; - measSensMatrix[0][5] = 0; - measSensMatrix[1][0] = measSensMatrix11[1][0]; - measSensMatrix[1][1] = measSensMatrix11[1][1]; - measSensMatrix[1][2] = measSensMatrix11[1][2]; - measSensMatrix[1][3] = 0; - measSensMatrix[1][4] = 0; - measSensMatrix[1][5] = 0; - measSensMatrix[2][0] = measSensMatrix11[2][0]; - measSensMatrix[2][1] = measSensMatrix11[2][1]; - measSensMatrix[2][2] = measSensMatrix11[2][2]; - measSensMatrix[2][3] = 0; - measSensMatrix[2][4] = 0; - measSensMatrix[2][5] = 0; - measSensMatrix[3][0] = measSensMatrix22[0][0]; - measSensMatrix[3][1] = measSensMatrix22[0][1]; - measSensMatrix[3][2] = measSensMatrix22[0][2]; - measSensMatrix[3][3] = 0; - measSensMatrix[3][4] = 0; - measSensMatrix[3][5] = 0; - measSensMatrix[4][0] = measSensMatrix22[1][0]; - measSensMatrix[4][1] = measSensMatrix22[1][1]; - measSensMatrix[4][2] = measSensMatrix22[1][2]; - measSensMatrix[4][3] = 0; - measSensMatrix[4][4] = 0; - measSensMatrix[4][5] = 0; - measSensMatrix[5][0] = measSensMatrix22[2][0]; - measSensMatrix[5][1] = measSensMatrix22[2][1]; - measSensMatrix[5][2] = measSensMatrix22[2][2]; - measSensMatrix[5][3] = 0; - measSensMatrix[5][4] = 0; - measSensMatrix[5][5] = 0; - - measCovMatrix[0][0] = covMatrix11[0][0]; - measCovMatrix[0][1] = covMatrix11[0][1]; - measCovMatrix[0][2] = covMatrix11[0][2]; - measCovMatrix[0][3] = 0; - measCovMatrix[0][4] = 0; - measCovMatrix[0][5] = 0; - measCovMatrix[1][0] = covMatrix11[1][0]; - measCovMatrix[1][1] = covMatrix11[1][1]; - measCovMatrix[1][2] = covMatrix11[1][2]; - measCovMatrix[1][3] = 0; - measCovMatrix[1][4] = 0; - measCovMatrix[1][5] = 0; - measCovMatrix[2][0] = covMatrix11[2][0]; - measCovMatrix[2][1] = covMatrix11[2][1]; - measCovMatrix[2][2] = covMatrix11[2][2]; - measCovMatrix[2][3] = 0; - measCovMatrix[2][4] = 0; - measCovMatrix[2][5] = 0; - measCovMatrix[3][0] = 0; - measCovMatrix[3][1] = 0; - measCovMatrix[3][2] = 0; - measCovMatrix[3][3] = covMatrix22[0][0]; - measCovMatrix[3][4] = covMatrix22[0][1]; - measCovMatrix[3][5] = covMatrix22[0][2]; - measCovMatrix[4][0] = 0; - measCovMatrix[4][1] = 0; - measCovMatrix[4][2] = 0; - measCovMatrix[4][3] = covMatrix22[1][0]; - measCovMatrix[4][4] = covMatrix22[1][1]; - measCovMatrix[4][5] = covMatrix22[1][2]; - measCovMatrix[5][0] = 0; - measCovMatrix[5][1] = 0; - measCovMatrix[5][2] = 0; - measCovMatrix[5][3] = covMatrix22[2][0]; - measCovMatrix[5][4] = covMatrix22[2][1]; - measCovMatrix[5][5] = covMatrix22[2][2]; - - measVec[0] = normSunB[0]; - measVec[1] = normSunB[1]; - measVec[2] = normSunB[2]; - measVec[3] = normMagB[0]; - measVec[4] = normMagB[1]; - measVec[5] = normMagB[2]; - - measEstVec[0] = sunEstB[0]; - measEstVec[1] = sunEstB[1]; - measEstVec[2] = sunEstB[2]; - measEstVec[3] = magEstB[0]; - measEstVec[4] = magEstB[1]; - measEstVec[5] = magEstB[2]; - - } - else if(sensorsAvail==3){ // ss / str valid - - measSensMatrix[0][0] = measSensMatrix11[0][0]; - measSensMatrix[0][1] = measSensMatrix11[0][1]; - measSensMatrix[0][2] = measSensMatrix11[0][2]; - measSensMatrix[0][3] = 0; - measSensMatrix[0][4] = 0; - measSensMatrix[0][5] = 0; - measSensMatrix[1][0] = measSensMatrix11[1][0]; - measSensMatrix[1][1] = measSensMatrix11[1][1]; - measSensMatrix[1][2] = measSensMatrix11[1][2]; - measSensMatrix[1][3] = 0; - measSensMatrix[1][4] = 0; - measSensMatrix[1][5] = 0; - measSensMatrix[2][0] = measSensMatrix11[2][0]; - measSensMatrix[2][1] = measSensMatrix11[2][1]; - measSensMatrix[2][2] = measSensMatrix11[2][2]; - measSensMatrix[2][3] = 0; - measSensMatrix[2][4] = 0; - measSensMatrix[2][5] = 0; - measSensMatrix[3][0] = measSensMatrix33[0][0]; - measSensMatrix[3][1] = measSensMatrix33[0][1]; - measSensMatrix[3][2] = measSensMatrix33[0][2]; - measSensMatrix[3][3] = 0; - measSensMatrix[3][4] = 0; - measSensMatrix[3][5] = 0; - measSensMatrix[4][0] = measSensMatrix33[1][0]; - measSensMatrix[4][1] = measSensMatrix33[1][1]; - measSensMatrix[4][2] = measSensMatrix33[1][2]; - measSensMatrix[4][3] = 0; - measSensMatrix[4][4] = 0; - measSensMatrix[4][5] = 0; - measSensMatrix[5][0] = measSensMatrix33[2][0]; - measSensMatrix[5][1] = measSensMatrix33[2][1]; - measSensMatrix[5][2] = measSensMatrix33[2][2]; - measSensMatrix[5][3] = 0; - measSensMatrix[5][4] = 0; - measSensMatrix[5][5] = 0; - - measCovMatrix[0][0] = covMatrix11[0][0]; - measCovMatrix[0][1] = covMatrix11[0][1]; - measCovMatrix[0][2] = covMatrix11[0][2]; - measCovMatrix[0][3] = 0; - measCovMatrix[0][4] = 0; - measCovMatrix[0][5] = 0; - measCovMatrix[1][0] = covMatrix11[1][0]; - measCovMatrix[1][1] = covMatrix11[1][1]; - measCovMatrix[1][2] = covMatrix11[1][2]; - measCovMatrix[1][3] = 0; - measCovMatrix[1][4] = 0; - measCovMatrix[1][5] = 0; - measCovMatrix[2][0] = covMatrix11[2][0]; - measCovMatrix[2][1] = covMatrix11[2][1]; - measCovMatrix[2][2] = covMatrix11[2][2]; - measCovMatrix[2][3] = 0; - measCovMatrix[2][4] = 0; - measCovMatrix[2][5] = 0; - measCovMatrix[3][0] = 0; - measCovMatrix[3][1] = 0; - measCovMatrix[3][2] = 0; - measCovMatrix[3][3] = covMatrix33[0][0]; - measCovMatrix[3][4] = covMatrix33[0][1]; - measCovMatrix[3][5] = covMatrix33[0][2]; - measCovMatrix[4][0] = 0; - measCovMatrix[4][1] = 0; - measCovMatrix[4][2] = 0; - measCovMatrix[4][3] = covMatrix33[1][0]; - measCovMatrix[4][4] = covMatrix33[1][1]; - measCovMatrix[4][5] = covMatrix33[1][2]; - measCovMatrix[5][0] = 0; - measCovMatrix[5][1] = 0; - measCovMatrix[5][2] = 0; - measCovMatrix[5][3] = covMatrix33[2][0]; - measCovMatrix[5][4] = covMatrix33[2][1]; - measCovMatrix[5][5] = covMatrix33[2][2]; - - measVec[0] = normSunB[0]; - measVec[1] = normSunB[1]; - measVec[2] = normSunB[2]; - measVec[3] = measVecQuat[0]; - measVec[4] = measVecQuat[1]; - measVec[5] = measVecQuat[2]; - - measEstVec[0] = sunEstB[0]; - measEstVec[1] = sunEstB[1]; - measEstVec[2] = sunEstB[2]; - measEstVec[3] = quatEstErr[0]; - measEstVec[4] = quatEstErr[1]; - measEstVec[5] = quatEstErr[2]; - - } - else if (sensorsAvail == 4){ // mag / str avail - - measSensMatrix[0][0] = measSensMatrix22[0][0]; - measSensMatrix[0][1] = measSensMatrix22[0][1]; - measSensMatrix[0][2] = measSensMatrix22[0][2]; - measSensMatrix[0][3] = 0; - measSensMatrix[0][4] = 0; - measSensMatrix[0][5] = 0; - measSensMatrix[1][0] = measSensMatrix22[1][0]; - measSensMatrix[1][1] = measSensMatrix22[1][1]; - measSensMatrix[1][2] = measSensMatrix22[1][2]; - measSensMatrix[1][3] = 0; - measSensMatrix[1][4] = 0; - measSensMatrix[1][5] = 0; - measSensMatrix[2][0] = measSensMatrix22[2][0]; - measSensMatrix[2][1] = measSensMatrix22[2][1]; - measSensMatrix[2][2] = measSensMatrix22[2][2]; - measSensMatrix[2][3] = 0; - measSensMatrix[2][4] = 0; - measSensMatrix[2][5] = 0; - measSensMatrix[3][0] = measSensMatrix33[0][0]; - measSensMatrix[3][1] = measSensMatrix33[0][1]; - measSensMatrix[3][2] = measSensMatrix33[0][2]; - measSensMatrix[3][3] = 0; - measSensMatrix[3][4] = 0; - measSensMatrix[3][5] = 0; - measSensMatrix[4][0] = measSensMatrix33[1][0]; - measSensMatrix[4][1] = measSensMatrix33[1][1]; - measSensMatrix[4][2] = measSensMatrix33[1][2]; - measSensMatrix[4][3] = 0; - measSensMatrix[4][4] = 0; - measSensMatrix[4][5] = 0; - measSensMatrix[5][0] = measSensMatrix33[2][0]; - measSensMatrix[5][1] = measSensMatrix33[2][1]; - measSensMatrix[5][2] = measSensMatrix33[2][2]; - measSensMatrix[5][3] = 0; - measSensMatrix[5][4] = 0; - measSensMatrix[5][5] = 0; - - measCovMatrix[0][0] = covMatrix22[0][0]; - measCovMatrix[0][1] = covMatrix22[0][1]; - measCovMatrix[0][2] = covMatrix22[0][2]; - measCovMatrix[0][3] = 0; - measCovMatrix[0][4] = 0; - measCovMatrix[0][5] = 0; - measCovMatrix[1][0] = covMatrix22[1][0]; - measCovMatrix[1][1] = covMatrix22[1][1]; - measCovMatrix[1][2] = covMatrix22[1][2]; - measCovMatrix[1][3] = 0; - measCovMatrix[1][4] = 0; - measCovMatrix[1][5] = 0; - measCovMatrix[2][0] = covMatrix22[2][0]; - measCovMatrix[2][1] = covMatrix22[2][1]; - measCovMatrix[2][2] = covMatrix22[2][2]; - measCovMatrix[2][3] = 0; - measCovMatrix[2][4] = 0; - measCovMatrix[2][5] = 0; - measCovMatrix[3][0] = 0; - measCovMatrix[3][1] = 0; - measCovMatrix[3][2] = 0; - measCovMatrix[3][3] = covMatrix33[0][0]; - measCovMatrix[3][4] = covMatrix33[0][1]; - measCovMatrix[3][5] = covMatrix33[0][2]; - measCovMatrix[4][0] = 0; - measCovMatrix[4][1] = 0; - measCovMatrix[4][2] = 0; - measCovMatrix[4][3] = covMatrix33[1][0]; - measCovMatrix[4][4] = covMatrix33[1][1]; - measCovMatrix[4][5] = covMatrix33[1][2]; - measCovMatrix[5][0] = 0; - measCovMatrix[5][1] = 0; - measCovMatrix[5][2] = 0; - measCovMatrix[5][3] = covMatrix33[2][0]; - measCovMatrix[5][4] = covMatrix33[2][1]; - measCovMatrix[5][5] = covMatrix33[2][2]; - - measVec[0] = normMagB[0]; - measVec[1] = normMagB[1]; - measVec[2] = normMagB[2]; - measVec[3] = measVecQuat[0]; - measVec[4] = measVecQuat[1]; - measVec[5] = measVecQuat[2]; - - measEstVec[0] = magEstB[0]; - measEstVec[1] = magEstB[1]; - measEstVec[2] = magEstB[2]; - measEstVec[3] = quatEstErr[0]; - measEstVec[4] = quatEstErr[1]; - measEstVec[5] = quatEstErr[2]; - - } - else if (sensorsAvail == 5){ // only ss - - measSensMatrix[0][0] = measSensMatrix11[0][0]; - measSensMatrix[0][1] = measSensMatrix11[0][1]; - measSensMatrix[0][2] = measSensMatrix11[0][2]; - measSensMatrix[0][3] = 0; - measSensMatrix[0][4] = 0; - measSensMatrix[0][5] = 0; - measSensMatrix[1][0] = measSensMatrix11[1][0]; - measSensMatrix[1][1] = measSensMatrix11[1][1]; - measSensMatrix[1][2] = measSensMatrix11[1][2]; - measSensMatrix[1][3] = 0; - measSensMatrix[1][4] = 0; - measSensMatrix[1][5] = 0; - measSensMatrix[2][0] = measSensMatrix11[2][0]; - measSensMatrix[2][1] = measSensMatrix11[2][1]; - measSensMatrix[2][2] = measSensMatrix11[2][2]; - measSensMatrix[2][3] = 0; - measSensMatrix[2][4] = 0; - measSensMatrix[2][5] = 0; - - measCovMatrix[0][0] = covMatrix11[0][0]; - measCovMatrix[0][1] = covMatrix11[0][1]; - measCovMatrix[0][2] = covMatrix11[0][2]; - measCovMatrix[1][0] = covMatrix11[1][0]; - measCovMatrix[1][1] = covMatrix11[1][1]; - measCovMatrix[1][2] = covMatrix11[1][2]; - measCovMatrix[2][0] = covMatrix11[2][0]; - measCovMatrix[2][1] = covMatrix11[2][1]; - measCovMatrix[2][2] = covMatrix11[2][2]; - - measVec[0] = normSunB[0]; - measVec[1] = normSunB[1]; - measVec[2] = normSunB[2]; - - measEstVec[0] = sunEstB[0]; - measEstVec[1] = sunEstB[1]; - measEstVec[2] = sunEstB[2]; - - } - else if (sensorsAvail == 6){ // only mag - - measSensMatrix[0][0] = measSensMatrix22[0][0]; - measSensMatrix[0][1] = measSensMatrix22[0][1]; - measSensMatrix[0][2] = measSensMatrix22[0][2]; - measSensMatrix[0][3] = 0; - measSensMatrix[0][4] = 0; - measSensMatrix[0][5] = 0; - measSensMatrix[1][0] = measSensMatrix22[1][0]; - measSensMatrix[1][1] = measSensMatrix22[1][1]; - measSensMatrix[1][2] = measSensMatrix22[1][2]; - measSensMatrix[1][3] = 0; - measSensMatrix[1][4] = 0; - measSensMatrix[1][5] = 0; - measSensMatrix[2][0] = measSensMatrix22[2][0]; - measSensMatrix[2][1] = measSensMatrix22[2][1]; - measSensMatrix[2][2] = measSensMatrix22[2][2]; - measSensMatrix[2][3] = 0; - measSensMatrix[2][4] = 0; - measSensMatrix[2][5] = 0; - - measCovMatrix[0][0] = covMatrix22[0][0]; - measCovMatrix[0][1] = covMatrix22[0][1]; - measCovMatrix[0][2] = covMatrix22[0][2]; - measCovMatrix[1][0] = covMatrix22[1][0]; - measCovMatrix[1][1] = covMatrix22[1][1]; - measCovMatrix[1][2] = covMatrix22[1][2]; - measCovMatrix[2][0] = covMatrix22[2][0]; - measCovMatrix[2][1] = covMatrix22[2][1]; - measCovMatrix[2][2] = covMatrix22[2][2]; - - measVec[0] = normMagB[0]; - measVec[1] = normMagB[1]; - measVec[2] = normMagB[2]; - - measEstVec[0] = magEstB[0]; - measEstVec[1] = magEstB[1]; - measEstVec[2] = magEstB[2]; - - } - else if (sensorsAvail == 7){ // only str - - measSensMatrix[0][0] = measSensMatrix33[0][0]; - measSensMatrix[0][1] = measSensMatrix33[0][1]; - measSensMatrix[0][2] = measSensMatrix33[0][2]; - measSensMatrix[0][3] = 0; - measSensMatrix[0][4] = 0; - measSensMatrix[0][5] = 0; - measSensMatrix[1][0] = measSensMatrix33[1][0]; - measSensMatrix[1][1] = measSensMatrix33[1][1]; - measSensMatrix[1][2] = measSensMatrix33[1][2]; - measSensMatrix[1][3] = 0; - measSensMatrix[1][4] = 0; - measSensMatrix[1][5] = 0; - measSensMatrix[2][0] = measSensMatrix33[2][0]; - measSensMatrix[2][1] = measSensMatrix33[2][1]; - measSensMatrix[2][2] = measSensMatrix33[2][2]; - measSensMatrix[2][3] = 0; - measSensMatrix[2][4] = 0; - measSensMatrix[2][5] = 0; - - measCovMatrix[0][0] = covMatrix33[0][0]; - measCovMatrix[0][1] = covMatrix33[0][1]; - measCovMatrix[0][2] = covMatrix33[0][2]; - measCovMatrix[1][0] = covMatrix33[1][0]; - measCovMatrix[1][1] = covMatrix33[1][1]; - measCovMatrix[1][2] = covMatrix33[1][2]; - measCovMatrix[2][0] = covMatrix33[2][0]; - measCovMatrix[2][1] = covMatrix33[2][1]; - measCovMatrix[2][2] = covMatrix33[2][2]; - - measVec[0] = measVecQuat[0]; - measVec[1] = measVecQuat[1]; - measVec[2] = measVecQuat[2]; - - measEstVec[0] = quatEstErr[0]; - measEstVec[1] = quatEstErr[1]; - measEstVec[2] = quatEstErr[2]; - - } - // Kalman Gain: [K = P * H' / (H * P * H' + R)] - double kalmanGain[6][MDF] = {{0}}, kalmanGain1[6][MDF] = {{0}}; - - double measSensMatrixTrans[6][MDF], residualCov[MDF][MDF], - residualCov1[6][MDF]; - // H * P * H' - MatrixOperations::transpose(*measSensMatrix,*measSensMatrixTrans,6,MDF); - MatrixOperations::multiply(*initialCovarianceMatrix,*measSensMatrixTrans,*residualCov1,6,6,MDF); - MatrixOperations::multiply(*measSensMatrix,*residualCov1,*residualCov,MDF,6,MDF); - // negative values, restrictions ? - // (H * P * H' + R) - MatrixOperations::add(*residualCov, *measCovMatrix, *residualCov, MDF, MDF); - // <> - double invResidualCov1[MDF] = {0}; - double invResidualCov[MDF][MDF] = {{0}}; - int inversionFailed = CholeskyDecomposition::invertCholesky(*residualCov,*invResidualCov,invResidualCov1,MDF); - if(inversionFailed) - { - validMekf = false; - return KALMAN_INVERSION_FAILED; // RETURN VALUE ? -- Like: Kalman Inversion Failed - } - - - // [K = P * H' / (H * P * H' + R)] - MatrixOperations::multiply(*measSensMatrixTrans,*invResidualCov,*kalmanGain1,6,MDF,MDF); - MatrixOperations::multiply(*initialCovarianceMatrix,*kalmanGain1,*kalmanGain,6,6,MDF); - - /* ------- UPDATE -STEP ---------*/ - - // Update Covariance Matrix: P_plus = (I-K*H)*P_min - double covMatPlus[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 identityMatrix[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}}; - double updateCov1[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}}; - MatrixOperations::multiply(*kalmanGain,*measSensMatrix,*updateCov1,6,MDF,MDF); - MatrixOperations::subtract(*identityMatrix,*updateCov1,*updateCov1,6,6); - MatrixOperations::multiply(*updateCov1,*initialCovarianceMatrix,*covMatPlus,6,6,6); - - // Error State Vector - double errStateVec[6] = {0,0,0,0,0,0}; - double errStateVec1[MDF] = {0}; - VectorOperations::subtract(measVec,measEstVec,errStateVec1,MDF); - MatrixOperations::multiply(*kalmanGain,errStateVec1,errStateVec,6,MDF,1); - - double errStateQuat[3] = {errStateVec[0], errStateVec[1], errStateVec[2]}; - double errStateGyroBias[3] = {errStateVec[3], errStateVec[4], errStateVec[5]}; - - // State Vector Elements - double xi1[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, - xi2[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; - MathOperations::skewMatrix(propagatedQuaternion, *xi2); - double identityMatrix3[3][3] = {{1,0,0},{0,1,0},{0,0,1}}; - MatrixOperations::multiplyScalar(*identityMatrix3, propagatedQuaternion[3], *xi1, 3, 3); - MatrixOperations::add(*xi1, *xi2, *xi1, 3, 3); - double xi[4][3] = {{xi1[0][0],xi1[0][1],xi1[0][2]}, - {xi1[1][0],xi1[1][1],xi1[1][2]}, - {xi1[2][0],xi1[2][1],xi1[2][2]}, - {-propagatedQuaternion[0],-propagatedQuaternion[1],-propagatedQuaternion[2]}}; - - double errQuatTerm[4] = {0,0,0,0}; - MatrixOperations::multiply(*xi, errStateQuat, errQuatTerm, 4, 3, 1); - VectorOperations::mulScalar(errQuatTerm, 0.5, errQuatTerm, 4); - VectorOperations::add(propagatedQuaternion, errQuatTerm, quatBJ, 4); - VectorOperations::normalize(quatBJ, quatBJ, 4); - - outputQuat[0] = quatBJ[0]; - outputQuat[1] = quatBJ[1]; - outputQuat[2] = quatBJ[2]; - outputQuat[3] = quatBJ[3]; - - double updatedGyroBias[3] = {0,0,0}; - VectorOperations::add(biasRMU, errStateGyroBias, updatedGyroBias, 3); - // Bias RMU State - biasRMU[0] = updatedGyroBias[0]; - biasRMU[1] = updatedGyroBias[1]; - biasRMU[2] = updatedGyroBias[2]; - - - /* ----------- PROPAGATION ----------*/ - //double sigmaU = kalmanFilterParameters->sensorNoiseBsRMU; - //double sigmaV = kalmanFilterParameters->sensorNoiseArwRmu; - double sigmaU = 3*3.141/180/3600; - double sigmaV = 3*0.0043*3.141/sqrt(10)/180; - - 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}}; - double rotRateEst[3] = {0,0,0}; - VectorOperations::subtract(rateRMUs_, updatedGyroBias, rotRateEst, 3); - double normRotEst =VectorOperations::norm(rotRateEst, 3); - double crossRotEst[3][3] = {{0,-rotRateEst[2],rotRateEst[1]}, - {rotRateEst[2],0,-rotRateEst[0]}, - {-rotRateEst[1],rotRateEst[0],0}}; - - // Corrected Sat Rate via Bias - outputSatRate[0] = rotRateEst[0]; - outputSatRate[1] = rotRateEst[1]; - outputSatRate[2] = rotRateEst[2]; - - // Discrete Process Noise Covariance Q - double discProcessNoiseCov[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 covQ1[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, - covQ2[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, - covQ3[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, - transCovQ2[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; - if(normRotEst*sampleTime< 3.141/10){ - double fact1 = sampleTime*pow(sigmaV,2)+pow(sampleTime,3)*pow(sigmaU,2/3); - MatrixOperations::multiplyScalar(*identityMatrix3, fact1, *covQ1, 3, 3); - double fact2 = -(0.5*pow(sampleTime,2)*pow(sigmaU,2)); - MatrixOperations::multiplyScalar(*identityMatrix3, fact2, *covQ2, 3, 3); - MatrixOperations::transpose(*covQ2, *transCovQ2, 3); - double fact3 = sampleTime*pow(sigmaU,2); - MatrixOperations::multiplyScalar(*identityMatrix3, fact3, *covQ3, 3, 3); - - discProcessNoiseCov[0][0] = covQ1[0][0]; - discProcessNoiseCov[0][1] = covQ1[0][1]; - discProcessNoiseCov[0][2] = covQ1[0][2]; - discProcessNoiseCov[0][3] = covQ2[0][0]; - discProcessNoiseCov[0][4] = covQ2[0][1]; - discProcessNoiseCov[0][5] = covQ2[0][2]; - discProcessNoiseCov[1][0] = covQ1[1][0]; - discProcessNoiseCov[1][1] = covQ1[1][1]; - discProcessNoiseCov[1][2] = covQ1[1][2]; - discProcessNoiseCov[1][3] = covQ2[1][0]; - discProcessNoiseCov[1][4] = covQ2[1][1]; - discProcessNoiseCov[1][5] = covQ2[1][2]; - discProcessNoiseCov[2][0] = covQ1[2][0]; - discProcessNoiseCov[2][1] = covQ1[2][1]; - discProcessNoiseCov[2][2] = covQ1[2][2]; - discProcessNoiseCov[2][3] = covQ2[2][0]; - discProcessNoiseCov[2][4] = covQ2[2][1]; - discProcessNoiseCov[2][5] = covQ2[2][2]; - discProcessNoiseCov[3][0] = transCovQ2[0][0]; - discProcessNoiseCov[3][1] = transCovQ2[0][1]; - discProcessNoiseCov[3][2] = transCovQ2[0][2]; - discProcessNoiseCov[3][3] = covQ3[0][0]; - discProcessNoiseCov[3][4] = covQ3[0][1]; - discProcessNoiseCov[3][5] = covQ3[0][2]; - discProcessNoiseCov[4][0] = transCovQ2[1][0]; - discProcessNoiseCov[4][1] = transCovQ2[1][1]; - discProcessNoiseCov[4][2] = transCovQ2[1][2]; - discProcessNoiseCov[4][3] = covQ3[1][0]; - discProcessNoiseCov[4][4] = covQ3[1][1]; - discProcessNoiseCov[4][5] = covQ3[1][2]; - discProcessNoiseCov[5][0] = transCovQ2[2][0]; - discProcessNoiseCov[5][1] = transCovQ2[2][1]; - discProcessNoiseCov[5][2] = transCovQ2[2][2]; - discProcessNoiseCov[5][3] = covQ3[2][0]; - discProcessNoiseCov[5][4] = covQ3[2][1]; - discProcessNoiseCov[5][5] = covQ3[2][2]; - } - else{ - //double fact1 = sampleTime*pow(sigmaV,2); - double covQ11[3][3],covQ12[3][3],covQ13[3][3]; - //MatrixOperations::multiplyScalar(*identityMatrix3, fact1, *covQ1, 3, 3); - double fact1 = (2*normRotEst+sampleTime-2*sin(normRotEst*sampleTime) - -pow(normRotEst,3)/3*pow(sampleTime,3))/pow(normRotEst,5); - MatrixOperations::multiply(*crossRotEst, *crossRotEst, *covQ11, 3, 3, 3); - MatrixOperations::multiplyScalar(*covQ11, fact1, *covQ11, 3, 3); - double fact2 = pow(sampleTime,3); - MatrixOperations::multiplyScalar(*identityMatrix3, fact2, *covQ12, 3, 3); - MatrixOperations::subtract(*covQ12, *covQ11, *covQ11, 3, 3); - double fact3 = sampleTime*pow(sigmaV,2); - MatrixOperations::multiplyScalar(*identityMatrix3, fact3, *covQ13, 3, 3); - MatrixOperations::add(*covQ13, *covQ11, *covQ1, 3, 3); - - double covQ21[3][3], covQ22[3][3], covQ23[3][3]; - double fact4 = (0.5*pow(normRotEst,2)*pow(sampleTime,2) - +cos(normRotEst*sampleTime)-1)/pow(normRotEst,4); - MatrixOperations::multiply(*crossRotEst, *crossRotEst, *covQ21, 3, 3, 3); - MatrixOperations::multiplyScalar(*covQ21, fact4, *covQ21, 3, 3); - double fact5 = 0.5*pow(sampleTime,2); - MatrixOperations::multiplyScalar(*identityMatrix3, fact5, *covQ22, 3, 3); - MatrixOperations::add(*covQ22, *covQ21, *covQ21, 3, 3); - double fact6 = normRotEst*sampleTime-sin(normRotEst*sampleTime)/pow(normRotEst,3); - MatrixOperations::multiplyScalar(*crossRotEst, fact6, *covQ23, 3, 3); - MatrixOperations::subtract(*covQ23, *covQ21, *covQ21, 3, 3); - double fact7 = pow(sigmaU,2); - MatrixOperations::multiplyScalar(*covQ21, fact7, *covQ2, 3, 3); - - MatrixOperations::multiplyScalar(*identityMatrix3, fact7, *covQ3, 3, 3); - - discProcessNoiseCov[0][0] = covQ1[0][0]; - discProcessNoiseCov[0][1] = covQ1[0][1]; - discProcessNoiseCov[0][2] = covQ1[0][2]; - discProcessNoiseCov[0][3] = covQ2[0][0]; - discProcessNoiseCov[0][4] = covQ2[0][1]; - discProcessNoiseCov[0][5] = covQ2[0][2]; - discProcessNoiseCov[1][0] = covQ1[1][0]; - discProcessNoiseCov[1][1] = covQ1[1][1]; - discProcessNoiseCov[1][2] = covQ1[1][2]; - discProcessNoiseCov[1][3] = covQ2[1][0]; - discProcessNoiseCov[1][4] = covQ2[1][1]; - discProcessNoiseCov[1][5] = covQ2[1][2]; - discProcessNoiseCov[2][0] = covQ1[2][0]; - discProcessNoiseCov[2][1] = covQ1[2][1]; - discProcessNoiseCov[2][2] = covQ1[2][2]; - discProcessNoiseCov[2][3] = covQ2[2][0]; - discProcessNoiseCov[2][4] = covQ2[2][1]; - discProcessNoiseCov[2][5] = covQ2[2][2]; - discProcessNoiseCov[3][0] = covQ2[0][0]; - discProcessNoiseCov[3][1] = covQ2[0][1]; - discProcessNoiseCov[3][2] = covQ2[0][2]; - discProcessNoiseCov[3][3] = covQ3[0][0]; - discProcessNoiseCov[3][4] = covQ3[0][1]; - discProcessNoiseCov[3][5] = covQ3[0][2]; - discProcessNoiseCov[4][0] = covQ2[1][0]; - discProcessNoiseCov[4][1] = covQ2[1][1]; - discProcessNoiseCov[4][2] = covQ2[1][2]; - discProcessNoiseCov[4][3] = covQ3[1][0]; - discProcessNoiseCov[4][4] = covQ3[1][1]; - discProcessNoiseCov[4][5] = covQ3[1][2]; - discProcessNoiseCov[5][0] = covQ2[2][0]; - discProcessNoiseCov[5][1] = covQ2[2][1]; - discProcessNoiseCov[5][2] = covQ2[2][2]; - discProcessNoiseCov[5][3] = covQ3[2][0]; - discProcessNoiseCov[5][4] = covQ3[2][1]; - discProcessNoiseCov[5][5] = covQ3[2][2]; - } - - // State Transition Matrix phi - double phi1[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, - phi2[3][3] = {{0,0,0},{0,0,0},{0,0,0}}, - 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[3][3],phi12[3][3]; - double fact1 = sin(normRotEst*sampleTime); - MatrixOperations::multiplyScalar(*crossRotEst, fact1, *phi11, 3, 3); - double fact2 = (1-cos(normRotEst*sampleTime))/pow(normRotEst,2); - MatrixOperations::multiply(*crossRotEst, *crossRotEst, *phi12, 3, 3, 3); - MatrixOperations::multiplyScalar(*phi12, fact2, *phi12, 3, 3); - MatrixOperations::subtract(*identityMatrix3, *phi11, *phi11, 3, 3); - MatrixOperations::add(*phi11, *phi12, *phi1, 3, 3); - - double phi21[3][3],phi22[3][3]; - MatrixOperations::multiplyScalar(*crossRotEst, fact2, *phi21, 3, 3); - MatrixOperations::multiplyScalar(*identityMatrix3, sampleTime, *phi22, 3, 3); - MatrixOperations::subtract(*phi21, *phi22, *phi21, 3, 3); - double fact3 = (normRotEst*sampleTime-sin(normRotEst*sampleTime)/pow(normRotEst,3)); - MatrixOperations::multiply(*crossRotEst, *crossRotEst, *phi22, 3, 3, 3); - MatrixOperations::multiplyScalar(*phi22, fact3, *phi22, 3, 3); - MatrixOperations::subtract(*phi21, *phi22, *phi2, 3, 3); - - phi[0][0] = phi1[0][0]; - phi[0][1] = phi1[0][1]; - phi[0][2] = phi1[0][2]; - phi[0][3] = phi2[0][0]; - phi[0][4] = phi2[0][1]; - phi[0][5] = phi2[0][2]; - phi[1][0] = phi1[1][0]; - phi[1][1] = phi1[1][1]; - phi[1][2] = phi1[1][2]; - phi[1][3] = phi2[1][0]; - phi[1][4] = phi2[1][1]; - phi[1][5] = phi2[1][2]; - phi[2][0] = phi1[2][0]; - phi[2][1] = phi1[2][1]; - phi[2][2] = phi1[2][2]; - phi[2][3] = phi2[2][0]; - phi[2][4] = phi2[2][1]; - phi[2][5] = phi2[2][2]; - - // Propagated Quaternion - double rotSin[3] = {0,0,0}, - omega1[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; - VectorOperations::mulScalar(rotRateEst, sinFac, rotSin, 3); - - double skewSin[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - MathOperations::skewMatrix(rotSin, *skewSin); - - MatrixOperations::multiplyScalar(*identityMatrix3, rotCos, *omega1, 3, 3); - MatrixOperations::subtract(*omega1, *skewSin, *omega1, 3, 3); - double omega[4][4] = {{omega1[0][0],omega1[0][1],omega1[0][2],rotSin[0]}, - {omega1[1][0],omega1[1][1],omega1[1][2],rotSin[1]}, - {omega1[2][0],omega1[2][1],omega1[2][2],rotSin[2]}, - {-rotSin[0],-rotSin[1],-rotSin[2],rotCos}}; - MatrixOperations::multiply(*omega, quatBJ, propagatedQuaternion, 4, 4, 1); - - // Update Covariance Matrix - double cov1[6][6], cov2[6][6], transDiscTimeMatrix[6][6], - transPhi[6][6]; - MatrixOperations::transpose(*discTimeMatrix, *transDiscTimeMatrix, 6); - MatrixOperations::multiply(*discProcessNoiseCov, *transDiscTimeMatrix, *cov1, 6, 6, 6); - MatrixOperations::multiply(*discTimeMatrix, *cov1, *cov1, 6, 6, 6); - - MatrixOperations::transpose(*phi, *transPhi, 6); - MatrixOperations::multiply(*covMatPlus, *transPhi, *cov2, 6, 6, 6); - MatrixOperations::multiply(*phi, *cov2, *cov2, 6, 6, 6); - - MatrixOperations::add(*cov2, *cov1, *initialCovarianceMatrix, 6, 6); - validMekf = true; - - - // Discrete Time Step - - // Check for new data in measurement -> SensorProcessing ? - - return returnvalue::OK; + 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 *outputQuat, double *outputSatRate) { + // Check for GYR Measurements + // AcsParameters mekfEstParams; + // loadAcsParameters(&mekfEstParams); + int MDF = 0; // Matrix Dimension Factor + if (!(*validGYRs_)) { + validMekf = false; + return KALMAN_NO_GYR_MEAS; + } + // Check for Model Calculations + else if (!(*validSSModel) || !(*validMagModel)) { + validMekf = false; + return KALMAN_NO_MODEL; + } + // Check Measurements available from SS, MAG, STR + if (*validSS && *validMagField_ && *validSTR_) { + sensorsAvail = 1; + MDF = 9; + } else if (*validSS && *validMagField_ && !(*validSTR_)) { + sensorsAvail = 2; + MDF = 6; + } else if (*validSS && !(*validMagField_) && *validSTR_) { + sensorsAvail = 3; + MDF = 6; + } else if (!(*validSS) && *validMagField_ && *validSTR_) { + sensorsAvail = 4; + MDF = 6; + } else if (*validSS && !(*validMagField_) && !(*validSTR_)) { + sensorsAvail = 5; + MDF = 3; + } else if (!(*validSS) && *validMagField_ && !(*validSTR_)) { + sensorsAvail = 6; + MDF = 3; + } else if (!(*validSS) && !(*validMagField_) && *validSTR_) { + sensorsAvail = 7; + MDF = 3; + } else { + sensorsAvail = 8; // no measurements + validMekf = false; + return returnvalue::FAILED; + } + + // If we are here, MEKF will perform + double sigmaSun = 0, sigmaMag = 0, sigmaStr = 0; + sigmaSun = kalmanFilterParameters->sensorNoiseSS; + sigmaMag = kalmanFilterParameters->sensorNoiseMAG; + sigmaStr = kalmanFilterParameters->sensorNoiseSTR; + + double normMagB[3] = {0, 0, 0}, normSunB[3] = {0, 0, 0}, normMagJ[3] = {0, 0, 0}, + normSunJ[3] = {0, 0, 0}; + VectorOperations::normalize(magneticField_, normMagB, 3); // b2 + VectorOperations::normalize(sunDir_, normSunB, 3); // b1 + VectorOperations::normalize(magFieldJ, normMagJ, 3); // r2 + VectorOperations::normalize(sunDirJ, normSunJ, 3); // r1 + + /*-------GAIN - UPDATE - STEP------*/ + double covMatrix11[3][3] = { + {pow(sigmaSun, 2), 0, 0}, {0, pow(sigmaSun, 2), 0}, {0, 0, pow(sigmaSun, 2)}}; + double covMatrix22[3][3] = { + {pow(sigmaMag, 2), 0, 0}, {0, pow(sigmaMag, 2), 0}, {0, 0, pow(sigmaMag, 2)}}; + double covMatrix33[3][3] = { + {pow(sigmaStr, 2), 0, 0}, {0, pow(sigmaStr, 2), 0}, {0, 0, pow(sigmaStr, 2)}}; + + double dcmBJ[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, sunEstB[3] = {0, 0, 0}, + magEstB[3] = {0, 0, 0}; + QuaternionOperations::toDcm(propagatedQuaternion, dcmBJ); + MatrixOperations::multiply(*dcmBJ, normSunJ, sunEstB, 3, 3, 1); + MatrixOperations::multiply(*dcmBJ, normMagJ, magEstB, 3, 3, 1); + double quatEstErr[3] = {0, 0, 0}; + + // Measurement Sensitivity Matrix + double measSensMatrix11[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; // ss + double measSensMatrix22[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; // mag + double measSensMatrix33[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}}; // str + MathOperations::skewMatrix(sunEstB, *measSensMatrix11); + MathOperations::skewMatrix(magEstB, *measSensMatrix22); + + double measVecQuat[3] = {0, 0, 0}; + if (*validSTR_) { + double quatError[4] = {0, 0, 0, 0}; + double invPropagatedQuat[4] = {0, 0, 0, 0}; + QuaternionOperations::inverse(propagatedQuaternion, invPropagatedQuat); + QuaternionOperations::multiply(quaternionSTR, invPropagatedQuat, quatError); + for (int i = 0; i < 3; i++) { + measVecQuat[i] = 2 * quatError[i] / quatError[3]; + } + } + // Adjust matrices based on valid measurements + double measSensMatrix[MDF][6], measCovMatrix[MDF][MDF], measVec[MDF], measEstVec[MDF]; + if (sensorsAvail == 1) { // All measurements valid + measSensMatrix[0][0] = measSensMatrix11[0][0]; + measSensMatrix[0][1] = measSensMatrix11[0][1]; + measSensMatrix[0][2] = measSensMatrix11[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix11[1][0]; + measSensMatrix[1][1] = measSensMatrix11[1][1]; + measSensMatrix[1][2] = measSensMatrix11[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix11[2][0]; + measSensMatrix[2][1] = measSensMatrix11[2][1]; + measSensMatrix[2][2] = measSensMatrix11[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + measSensMatrix[3][0] = measSensMatrix22[0][0]; + measSensMatrix[3][1] = measSensMatrix22[0][1]; + measSensMatrix[3][2] = measSensMatrix22[0][2]; + measSensMatrix[3][3] = 0; + measSensMatrix[3][4] = 0; + measSensMatrix[3][5] = 0; + measSensMatrix[4][0] = measSensMatrix22[1][0]; + measSensMatrix[4][1] = measSensMatrix22[1][1]; + measSensMatrix[4][2] = measSensMatrix22[1][2]; + measSensMatrix[4][3] = 0; + measSensMatrix[4][4] = 0; + measSensMatrix[4][5] = 0; + measSensMatrix[5][0] = measSensMatrix22[2][0]; + measSensMatrix[5][1] = measSensMatrix22[2][1]; + measSensMatrix[5][2] = measSensMatrix22[2][2]; + measSensMatrix[5][3] = 0; + measSensMatrix[5][4] = 0; + measSensMatrix[5][5] = 0; + measSensMatrix[6][0] = measSensMatrix33[0][0]; + measSensMatrix[6][1] = measSensMatrix33[0][1]; + measSensMatrix[6][2] = measSensMatrix33[0][2]; + measSensMatrix[6][3] = 0; + measSensMatrix[6][4] = 0; + measSensMatrix[6][5] = 0; + measSensMatrix[7][0] = measSensMatrix33[1][0]; + measSensMatrix[7][1] = measSensMatrix33[1][1]; + measSensMatrix[7][2] = measSensMatrix33[1][2]; + measSensMatrix[7][3] = 0; + measSensMatrix[7][4] = 0; + measSensMatrix[7][5] = 0; + measSensMatrix[8][0] = measSensMatrix33[2][0]; + measSensMatrix[8][1] = measSensMatrix33[2][1]; + measSensMatrix[8][2] = measSensMatrix33[2][2]; + measSensMatrix[8][3] = 0; + measSensMatrix[8][4] = 0; + measSensMatrix[8][5] = 0; + + measCovMatrix[0][0] = covMatrix11[0][0]; + measCovMatrix[0][1] = covMatrix11[0][1]; + measCovMatrix[0][2] = covMatrix11[0][2]; + measCovMatrix[0][3] = 0; + measCovMatrix[0][4] = 0; + measCovMatrix[0][5] = 0; + measCovMatrix[0][6] = 0; + measCovMatrix[0][7] = 0; + measCovMatrix[0][8] = 0; + measCovMatrix[1][0] = covMatrix11[1][0]; + measCovMatrix[1][1] = covMatrix11[1][1]; + measCovMatrix[1][2] = covMatrix11[1][2]; + measCovMatrix[1][3] = 0; + measCovMatrix[1][4] = 0; + measCovMatrix[1][5] = 0; + measCovMatrix[1][6] = 0; + measCovMatrix[1][7] = 0; + measCovMatrix[1][8] = 0; + measCovMatrix[2][0] = covMatrix11[2][0]; + measCovMatrix[2][1] = covMatrix11[2][1]; + measCovMatrix[2][2] = covMatrix11[2][2]; + measCovMatrix[2][3] = 0; + measCovMatrix[2][4] = 0; + measCovMatrix[2][5] = 0; + measCovMatrix[2][6] = 0; + measCovMatrix[2][7] = 0; + measCovMatrix[2][8] = 0; + measCovMatrix[3][0] = 0; + measCovMatrix[3][1] = 0; + measCovMatrix[3][2] = 0; + measCovMatrix[3][3] = covMatrix22[0][0]; + measCovMatrix[3][4] = covMatrix22[0][1]; + measCovMatrix[3][5] = covMatrix22[0][2]; + measCovMatrix[3][6] = 0; + measCovMatrix[3][7] = 0; + measCovMatrix[3][8] = 0; + measCovMatrix[4][0] = 0; + measCovMatrix[4][1] = 0; + measCovMatrix[4][2] = 0; + measCovMatrix[4][3] = covMatrix22[1][0]; + measCovMatrix[4][4] = covMatrix22[1][1]; + measCovMatrix[4][5] = covMatrix22[1][2]; + measCovMatrix[4][6] = 0; + measCovMatrix[4][7] = 0; + measCovMatrix[4][8] = 0; + measCovMatrix[5][0] = 0; + measCovMatrix[5][1] = 0; + measCovMatrix[5][2] = 0; + measCovMatrix[5][3] = covMatrix22[2][0]; + measCovMatrix[5][4] = covMatrix22[2][1]; + measCovMatrix[5][5] = covMatrix22[2][2]; + measCovMatrix[5][6] = 0; + measCovMatrix[5][7] = 0; + measCovMatrix[5][8] = 0; + measCovMatrix[6][0] = 0; + measCovMatrix[6][1] = 0; + measCovMatrix[6][2] = 0; + measCovMatrix[6][3] = 0; + measCovMatrix[6][4] = 0; + measCovMatrix[6][5] = 0; + measCovMatrix[6][6] = covMatrix33[0][0]; + measCovMatrix[6][7] = covMatrix33[0][1]; + measCovMatrix[6][8] = covMatrix33[0][2]; + measCovMatrix[7][0] = 0; + measCovMatrix[7][1] = 0; + measCovMatrix[7][2] = 0; + measCovMatrix[7][3] = 0; + measCovMatrix[7][4] = 0; + measCovMatrix[7][5] = 0; + measCovMatrix[7][6] = covMatrix33[1][0]; + measCovMatrix[7][7] = covMatrix33[1][1]; + measCovMatrix[7][8] = covMatrix33[1][2]; + measCovMatrix[8][0] = 0; + measCovMatrix[8][1] = 0; + measCovMatrix[8][2] = 0; + measCovMatrix[8][3] = 0; + measCovMatrix[8][4] = 0; + measCovMatrix[8][5] = 0; + measCovMatrix[8][6] = covMatrix33[2][0]; + measCovMatrix[8][7] = covMatrix33[2][1]; + measCovMatrix[8][8] = covMatrix33[2][2]; + + measVec[0] = normSunB[0]; + measVec[1] = normSunB[1]; + measVec[2] = normSunB[2]; + measVec[3] = normMagB[0]; + measVec[4] = normMagB[1]; + measVec[5] = normMagB[2]; + measVec[6] = measVecQuat[0]; + measVec[7] = measVecQuat[1]; + measVec[8] = measVecQuat[2]; + + measEstVec[0] = sunEstB[0]; + measEstVec[1] = sunEstB[1]; + measEstVec[2] = sunEstB[2]; + measEstVec[3] = magEstB[0]; + measEstVec[4] = magEstB[1]; + measEstVec[5] = magEstB[2]; + measEstVec[6] = quatEstErr[0]; + measEstVec[7] = quatEstErr[1]; + measEstVec[8] = quatEstErr[2]; + + } else if (sensorsAvail == 2) { // ss / mag valid + measSensMatrix[0][0] = measSensMatrix11[0][0]; + measSensMatrix[0][1] = measSensMatrix11[0][1]; + measSensMatrix[0][2] = measSensMatrix11[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix11[1][0]; + measSensMatrix[1][1] = measSensMatrix11[1][1]; + measSensMatrix[1][2] = measSensMatrix11[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix11[2][0]; + measSensMatrix[2][1] = measSensMatrix11[2][1]; + measSensMatrix[2][2] = measSensMatrix11[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + measSensMatrix[3][0] = measSensMatrix22[0][0]; + measSensMatrix[3][1] = measSensMatrix22[0][1]; + measSensMatrix[3][2] = measSensMatrix22[0][2]; + measSensMatrix[3][3] = 0; + measSensMatrix[3][4] = 0; + measSensMatrix[3][5] = 0; + measSensMatrix[4][0] = measSensMatrix22[1][0]; + measSensMatrix[4][1] = measSensMatrix22[1][1]; + measSensMatrix[4][2] = measSensMatrix22[1][2]; + measSensMatrix[4][3] = 0; + measSensMatrix[4][4] = 0; + measSensMatrix[4][5] = 0; + measSensMatrix[5][0] = measSensMatrix22[2][0]; + measSensMatrix[5][1] = measSensMatrix22[2][1]; + measSensMatrix[5][2] = measSensMatrix22[2][2]; + measSensMatrix[5][3] = 0; + measSensMatrix[5][4] = 0; + measSensMatrix[5][5] = 0; + + measCovMatrix[0][0] = covMatrix11[0][0]; + measCovMatrix[0][1] = covMatrix11[0][1]; + measCovMatrix[0][2] = covMatrix11[0][2]; + measCovMatrix[0][3] = 0; + measCovMatrix[0][4] = 0; + measCovMatrix[0][5] = 0; + measCovMatrix[1][0] = covMatrix11[1][0]; + measCovMatrix[1][1] = covMatrix11[1][1]; + measCovMatrix[1][2] = covMatrix11[1][2]; + measCovMatrix[1][3] = 0; + measCovMatrix[1][4] = 0; + measCovMatrix[1][5] = 0; + measCovMatrix[2][0] = covMatrix11[2][0]; + measCovMatrix[2][1] = covMatrix11[2][1]; + measCovMatrix[2][2] = covMatrix11[2][2]; + measCovMatrix[2][3] = 0; + measCovMatrix[2][4] = 0; + measCovMatrix[2][5] = 0; + measCovMatrix[3][0] = 0; + measCovMatrix[3][1] = 0; + measCovMatrix[3][2] = 0; + measCovMatrix[3][3] = covMatrix22[0][0]; + measCovMatrix[3][4] = covMatrix22[0][1]; + measCovMatrix[3][5] = covMatrix22[0][2]; + measCovMatrix[4][0] = 0; + measCovMatrix[4][1] = 0; + measCovMatrix[4][2] = 0; + measCovMatrix[4][3] = covMatrix22[1][0]; + measCovMatrix[4][4] = covMatrix22[1][1]; + measCovMatrix[4][5] = covMatrix22[1][2]; + measCovMatrix[5][0] = 0; + measCovMatrix[5][1] = 0; + measCovMatrix[5][2] = 0; + measCovMatrix[5][3] = covMatrix22[2][0]; + measCovMatrix[5][4] = covMatrix22[2][1]; + measCovMatrix[5][5] = covMatrix22[2][2]; + + measVec[0] = normSunB[0]; + measVec[1] = normSunB[1]; + measVec[2] = normSunB[2]; + measVec[3] = normMagB[0]; + measVec[4] = normMagB[1]; + measVec[5] = normMagB[2]; + + measEstVec[0] = sunEstB[0]; + measEstVec[1] = sunEstB[1]; + measEstVec[2] = sunEstB[2]; + measEstVec[3] = magEstB[0]; + measEstVec[4] = magEstB[1]; + measEstVec[5] = magEstB[2]; + + } else if (sensorsAvail == 3) { // ss / str valid + + measSensMatrix[0][0] = measSensMatrix11[0][0]; + measSensMatrix[0][1] = measSensMatrix11[0][1]; + measSensMatrix[0][2] = measSensMatrix11[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix11[1][0]; + measSensMatrix[1][1] = measSensMatrix11[1][1]; + measSensMatrix[1][2] = measSensMatrix11[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix11[2][0]; + measSensMatrix[2][1] = measSensMatrix11[2][1]; + measSensMatrix[2][2] = measSensMatrix11[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + measSensMatrix[3][0] = measSensMatrix33[0][0]; + measSensMatrix[3][1] = measSensMatrix33[0][1]; + measSensMatrix[3][2] = measSensMatrix33[0][2]; + measSensMatrix[3][3] = 0; + measSensMatrix[3][4] = 0; + measSensMatrix[3][5] = 0; + measSensMatrix[4][0] = measSensMatrix33[1][0]; + measSensMatrix[4][1] = measSensMatrix33[1][1]; + measSensMatrix[4][2] = measSensMatrix33[1][2]; + measSensMatrix[4][3] = 0; + measSensMatrix[4][4] = 0; + measSensMatrix[4][5] = 0; + measSensMatrix[5][0] = measSensMatrix33[2][0]; + measSensMatrix[5][1] = measSensMatrix33[2][1]; + measSensMatrix[5][2] = measSensMatrix33[2][2]; + measSensMatrix[5][3] = 0; + measSensMatrix[5][4] = 0; + measSensMatrix[5][5] = 0; + + measCovMatrix[0][0] = covMatrix11[0][0]; + measCovMatrix[0][1] = covMatrix11[0][1]; + measCovMatrix[0][2] = covMatrix11[0][2]; + measCovMatrix[0][3] = 0; + measCovMatrix[0][4] = 0; + measCovMatrix[0][5] = 0; + measCovMatrix[1][0] = covMatrix11[1][0]; + measCovMatrix[1][1] = covMatrix11[1][1]; + measCovMatrix[1][2] = covMatrix11[1][2]; + measCovMatrix[1][3] = 0; + measCovMatrix[1][4] = 0; + measCovMatrix[1][5] = 0; + measCovMatrix[2][0] = covMatrix11[2][0]; + measCovMatrix[2][1] = covMatrix11[2][1]; + measCovMatrix[2][2] = covMatrix11[2][2]; + measCovMatrix[2][3] = 0; + measCovMatrix[2][4] = 0; + measCovMatrix[2][5] = 0; + measCovMatrix[3][0] = 0; + measCovMatrix[3][1] = 0; + measCovMatrix[3][2] = 0; + measCovMatrix[3][3] = covMatrix33[0][0]; + measCovMatrix[3][4] = covMatrix33[0][1]; + measCovMatrix[3][5] = covMatrix33[0][2]; + measCovMatrix[4][0] = 0; + measCovMatrix[4][1] = 0; + measCovMatrix[4][2] = 0; + measCovMatrix[4][3] = covMatrix33[1][0]; + measCovMatrix[4][4] = covMatrix33[1][1]; + measCovMatrix[4][5] = covMatrix33[1][2]; + measCovMatrix[5][0] = 0; + measCovMatrix[5][1] = 0; + measCovMatrix[5][2] = 0; + measCovMatrix[5][3] = covMatrix33[2][0]; + measCovMatrix[5][4] = covMatrix33[2][1]; + measCovMatrix[5][5] = covMatrix33[2][2]; + + measVec[0] = normSunB[0]; + measVec[1] = normSunB[1]; + measVec[2] = normSunB[2]; + measVec[3] = measVecQuat[0]; + measVec[4] = measVecQuat[1]; + measVec[5] = measVecQuat[2]; + + measEstVec[0] = sunEstB[0]; + measEstVec[1] = sunEstB[1]; + measEstVec[2] = sunEstB[2]; + measEstVec[3] = quatEstErr[0]; + measEstVec[4] = quatEstErr[1]; + measEstVec[5] = quatEstErr[2]; + + } else if (sensorsAvail == 4) { // mag / str avail + + measSensMatrix[0][0] = measSensMatrix22[0][0]; + measSensMatrix[0][1] = measSensMatrix22[0][1]; + measSensMatrix[0][2] = measSensMatrix22[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix22[1][0]; + measSensMatrix[1][1] = measSensMatrix22[1][1]; + measSensMatrix[1][2] = measSensMatrix22[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix22[2][0]; + measSensMatrix[2][1] = measSensMatrix22[2][1]; + measSensMatrix[2][2] = measSensMatrix22[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + measSensMatrix[3][0] = measSensMatrix33[0][0]; + measSensMatrix[3][1] = measSensMatrix33[0][1]; + measSensMatrix[3][2] = measSensMatrix33[0][2]; + measSensMatrix[3][3] = 0; + measSensMatrix[3][4] = 0; + measSensMatrix[3][5] = 0; + measSensMatrix[4][0] = measSensMatrix33[1][0]; + measSensMatrix[4][1] = measSensMatrix33[1][1]; + measSensMatrix[4][2] = measSensMatrix33[1][2]; + measSensMatrix[4][3] = 0; + measSensMatrix[4][4] = 0; + measSensMatrix[4][5] = 0; + measSensMatrix[5][0] = measSensMatrix33[2][0]; + measSensMatrix[5][1] = measSensMatrix33[2][1]; + measSensMatrix[5][2] = measSensMatrix33[2][2]; + measSensMatrix[5][3] = 0; + measSensMatrix[5][4] = 0; + measSensMatrix[5][5] = 0; + + measCovMatrix[0][0] = covMatrix22[0][0]; + measCovMatrix[0][1] = covMatrix22[0][1]; + measCovMatrix[0][2] = covMatrix22[0][2]; + measCovMatrix[0][3] = 0; + measCovMatrix[0][4] = 0; + measCovMatrix[0][5] = 0; + measCovMatrix[1][0] = covMatrix22[1][0]; + measCovMatrix[1][1] = covMatrix22[1][1]; + measCovMatrix[1][2] = covMatrix22[1][2]; + measCovMatrix[1][3] = 0; + measCovMatrix[1][4] = 0; + measCovMatrix[1][5] = 0; + measCovMatrix[2][0] = covMatrix22[2][0]; + measCovMatrix[2][1] = covMatrix22[2][1]; + measCovMatrix[2][2] = covMatrix22[2][2]; + measCovMatrix[2][3] = 0; + measCovMatrix[2][4] = 0; + measCovMatrix[2][5] = 0; + measCovMatrix[3][0] = 0; + measCovMatrix[3][1] = 0; + measCovMatrix[3][2] = 0; + measCovMatrix[3][3] = covMatrix33[0][0]; + measCovMatrix[3][4] = covMatrix33[0][1]; + measCovMatrix[3][5] = covMatrix33[0][2]; + measCovMatrix[4][0] = 0; + measCovMatrix[4][1] = 0; + measCovMatrix[4][2] = 0; + measCovMatrix[4][3] = covMatrix33[1][0]; + measCovMatrix[4][4] = covMatrix33[1][1]; + measCovMatrix[4][5] = covMatrix33[1][2]; + measCovMatrix[5][0] = 0; + measCovMatrix[5][1] = 0; + measCovMatrix[5][2] = 0; + measCovMatrix[5][3] = covMatrix33[2][0]; + measCovMatrix[5][4] = covMatrix33[2][1]; + measCovMatrix[5][5] = covMatrix33[2][2]; + + measVec[0] = normMagB[0]; + measVec[1] = normMagB[1]; + measVec[2] = normMagB[2]; + measVec[3] = measVecQuat[0]; + measVec[4] = measVecQuat[1]; + measVec[5] = measVecQuat[2]; + + measEstVec[0] = magEstB[0]; + measEstVec[1] = magEstB[1]; + measEstVec[2] = magEstB[2]; + measEstVec[3] = quatEstErr[0]; + measEstVec[4] = quatEstErr[1]; + measEstVec[5] = quatEstErr[2]; + + } else if (sensorsAvail == 5) { // only ss + + measSensMatrix[0][0] = measSensMatrix11[0][0]; + measSensMatrix[0][1] = measSensMatrix11[0][1]; + measSensMatrix[0][2] = measSensMatrix11[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix11[1][0]; + measSensMatrix[1][1] = measSensMatrix11[1][1]; + measSensMatrix[1][2] = measSensMatrix11[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix11[2][0]; + measSensMatrix[2][1] = measSensMatrix11[2][1]; + measSensMatrix[2][2] = measSensMatrix11[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + + measCovMatrix[0][0] = covMatrix11[0][0]; + measCovMatrix[0][1] = covMatrix11[0][1]; + measCovMatrix[0][2] = covMatrix11[0][2]; + measCovMatrix[1][0] = covMatrix11[1][0]; + measCovMatrix[1][1] = covMatrix11[1][1]; + measCovMatrix[1][2] = covMatrix11[1][2]; + measCovMatrix[2][0] = covMatrix11[2][0]; + measCovMatrix[2][1] = covMatrix11[2][1]; + measCovMatrix[2][2] = covMatrix11[2][2]; + + measVec[0] = normSunB[0]; + measVec[1] = normSunB[1]; + measVec[2] = normSunB[2]; + + measEstVec[0] = sunEstB[0]; + measEstVec[1] = sunEstB[1]; + measEstVec[2] = sunEstB[2]; + + } else if (sensorsAvail == 6) { // only mag + + measSensMatrix[0][0] = measSensMatrix22[0][0]; + measSensMatrix[0][1] = measSensMatrix22[0][1]; + measSensMatrix[0][2] = measSensMatrix22[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix22[1][0]; + measSensMatrix[1][1] = measSensMatrix22[1][1]; + measSensMatrix[1][2] = measSensMatrix22[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix22[2][0]; + measSensMatrix[2][1] = measSensMatrix22[2][1]; + measSensMatrix[2][2] = measSensMatrix22[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + + measCovMatrix[0][0] = covMatrix22[0][0]; + measCovMatrix[0][1] = covMatrix22[0][1]; + measCovMatrix[0][2] = covMatrix22[0][2]; + measCovMatrix[1][0] = covMatrix22[1][0]; + measCovMatrix[1][1] = covMatrix22[1][1]; + measCovMatrix[1][2] = covMatrix22[1][2]; + measCovMatrix[2][0] = covMatrix22[2][0]; + measCovMatrix[2][1] = covMatrix22[2][1]; + measCovMatrix[2][2] = covMatrix22[2][2]; + + measVec[0] = normMagB[0]; + measVec[1] = normMagB[1]; + measVec[2] = normMagB[2]; + + measEstVec[0] = magEstB[0]; + measEstVec[1] = magEstB[1]; + measEstVec[2] = magEstB[2]; + + } else if (sensorsAvail == 7) { // only str + + measSensMatrix[0][0] = measSensMatrix33[0][0]; + measSensMatrix[0][1] = measSensMatrix33[0][1]; + measSensMatrix[0][2] = measSensMatrix33[0][2]; + measSensMatrix[0][3] = 0; + measSensMatrix[0][4] = 0; + measSensMatrix[0][5] = 0; + measSensMatrix[1][0] = measSensMatrix33[1][0]; + measSensMatrix[1][1] = measSensMatrix33[1][1]; + measSensMatrix[1][2] = measSensMatrix33[1][2]; + measSensMatrix[1][3] = 0; + measSensMatrix[1][4] = 0; + measSensMatrix[1][5] = 0; + measSensMatrix[2][0] = measSensMatrix33[2][0]; + measSensMatrix[2][1] = measSensMatrix33[2][1]; + measSensMatrix[2][2] = measSensMatrix33[2][2]; + measSensMatrix[2][3] = 0; + measSensMatrix[2][4] = 0; + measSensMatrix[2][5] = 0; + + measCovMatrix[0][0] = covMatrix33[0][0]; + measCovMatrix[0][1] = covMatrix33[0][1]; + measCovMatrix[0][2] = covMatrix33[0][2]; + measCovMatrix[1][0] = covMatrix33[1][0]; + measCovMatrix[1][1] = covMatrix33[1][1]; + measCovMatrix[1][2] = covMatrix33[1][2]; + measCovMatrix[2][0] = covMatrix33[2][0]; + measCovMatrix[2][1] = covMatrix33[2][1]; + measCovMatrix[2][2] = covMatrix33[2][2]; + + measVec[0] = measVecQuat[0]; + measVec[1] = measVecQuat[1]; + measVec[2] = measVecQuat[2]; + + measEstVec[0] = quatEstErr[0]; + measEstVec[1] = quatEstErr[1]; + measEstVec[2] = quatEstErr[2]; + } + // Kalman Gain: [K = P * H' / (H * P * H' + R)] + double kalmanGain[6][MDF] = {{0}}, kalmanGain1[6][MDF] = {{0}}; + + double measSensMatrixTrans[6][MDF], residualCov[MDF][MDF], residualCov1[6][MDF]; + // H * P * H' + MatrixOperations::transpose(*measSensMatrix, *measSensMatrixTrans, 6, MDF); + MatrixOperations::multiply(*initialCovarianceMatrix, *measSensMatrixTrans, *residualCov1, + 6, 6, MDF); + MatrixOperations::multiply(*measSensMatrix, *residualCov1, *residualCov, MDF, 6, MDF); + // negative values, restrictions ? + // (H * P * H' + R) + MatrixOperations::add(*residualCov, *measCovMatrix, *residualCov, MDF, MDF); + // <> + double invResidualCov1[MDF] = {0}; + double invResidualCov[MDF][MDF] = {{0}}; + int inversionFailed = CholeskyDecomposition::invertCholesky(*residualCov, *invResidualCov, + invResidualCov1, MDF); + if (inversionFailed) { + validMekf = false; + return KALMAN_INVERSION_FAILED; // RETURN VALUE ? -- Like: Kalman Inversion Failed + } + + // [K = P * H' / (H * P * H' + R)] + MatrixOperations::multiply(*measSensMatrixTrans, *invResidualCov, *kalmanGain1, 6, MDF, + MDF); + MatrixOperations::multiply(*initialCovarianceMatrix, *kalmanGain1, *kalmanGain, 6, 6, + MDF); + + /* ------- UPDATE -STEP ---------*/ + + // Update Covariance Matrix: P_plus = (I-K*H)*P_min + double covMatPlus[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 identityMatrix[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}}; + double updateCov1[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}}; + MatrixOperations::multiply(*kalmanGain, *measSensMatrix, *updateCov1, 6, MDF, MDF); + MatrixOperations::subtract(*identityMatrix, *updateCov1, *updateCov1, 6, 6); + MatrixOperations::multiply(*updateCov1, *initialCovarianceMatrix, *covMatPlus, 6, 6, 6); + + // Error State Vector + double errStateVec[6] = {0, 0, 0, 0, 0, 0}; + double errStateVec1[MDF] = {0}; + VectorOperations::subtract(measVec, measEstVec, errStateVec1, MDF); + MatrixOperations::multiply(*kalmanGain, errStateVec1, errStateVec, 6, MDF, 1); + + double errStateQuat[3] = {errStateVec[0], errStateVec[1], errStateVec[2]}; + double errStateGyroBias[3] = {errStateVec[3], errStateVec[4], errStateVec[5]}; + + // State Vector Elements + double xi1[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, + xi2[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MathOperations::skewMatrix(propagatedQuaternion, *xi2); + double identityMatrix3[3][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}}; + MatrixOperations::multiplyScalar(*identityMatrix3, propagatedQuaternion[3], *xi1, 3, 3); + MatrixOperations::add(*xi1, *xi2, *xi1, 3, 3); + double xi[4][3] = { + {xi1[0][0], xi1[0][1], xi1[0][2]}, + {xi1[1][0], xi1[1][1], xi1[1][2]}, + {xi1[2][0], xi1[2][1], xi1[2][2]}, + {-propagatedQuaternion[0], -propagatedQuaternion[1], -propagatedQuaternion[2]}}; + + double errQuatTerm[4] = {0, 0, 0, 0}; + MatrixOperations::multiply(*xi, errStateQuat, errQuatTerm, 4, 3, 1); + VectorOperations::mulScalar(errQuatTerm, 0.5, errQuatTerm, 4); + VectorOperations::add(propagatedQuaternion, errQuatTerm, quatBJ, 4); + VectorOperations::normalize(quatBJ, quatBJ, 4); + + outputQuat[0] = quatBJ[0]; + outputQuat[1] = quatBJ[1]; + outputQuat[2] = quatBJ[2]; + outputQuat[3] = quatBJ[3]; + + double updatedGyroBias[3] = {0, 0, 0}; + VectorOperations::add(biasGYR, errStateGyroBias, updatedGyroBias, 3); + // Bias GYR State + biasGYR[0] = updatedGyroBias[0]; + biasGYR[1] = updatedGyroBias[1]; + biasGYR[2] = updatedGyroBias[2]; + + /* ----------- PROPAGATION ----------*/ + // double sigmaU = kalmanFilterParameters->sensorNoiseBsGYR; + // double sigmaV = kalmanFilterParameters->sensorNoiseArwGYR; + double sigmaU = 3 * 3.141 / 180 / 3600; + double sigmaV = 3 * 0.0043 * 3.141 / sqrt(10) / 180; + + 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}}; + double rotRateEst[3] = {0, 0, 0}; + VectorOperations::subtract(rateGYRs_, updatedGyroBias, rotRateEst, 3); + double normRotEst = VectorOperations::norm(rotRateEst, 3); + double crossRotEst[3][3] = {{0, -rotRateEst[2], rotRateEst[1]}, + {rotRateEst[2], 0, -rotRateEst[0]}, + {-rotRateEst[1], rotRateEst[0], 0}}; + + // Corrected Sat Rate via Bias + outputSatRate[0] = rotRateEst[0]; + outputSatRate[1] = rotRateEst[1]; + outputSatRate[2] = rotRateEst[2]; + + // Discrete Process Noise Covariance Q + double discProcessNoiseCov[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 covQ1[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, + covQ2[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, + covQ3[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, + transCovQ2[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + if (normRotEst * sampleTime < 3.141 / 10) { + double fact1 = sampleTime * pow(sigmaV, 2) + pow(sampleTime, 3) * pow(sigmaU, 2 / 3); + MatrixOperations::multiplyScalar(*identityMatrix3, fact1, *covQ1, 3, 3); + double fact2 = -(0.5 * pow(sampleTime, 2) * pow(sigmaU, 2)); + MatrixOperations::multiplyScalar(*identityMatrix3, fact2, *covQ2, 3, 3); + MatrixOperations::transpose(*covQ2, *transCovQ2, 3); + double fact3 = sampleTime * pow(sigmaU, 2); + MatrixOperations::multiplyScalar(*identityMatrix3, fact3, *covQ3, 3, 3); + + discProcessNoiseCov[0][0] = covQ1[0][0]; + discProcessNoiseCov[0][1] = covQ1[0][1]; + discProcessNoiseCov[0][2] = covQ1[0][2]; + discProcessNoiseCov[0][3] = covQ2[0][0]; + discProcessNoiseCov[0][4] = covQ2[0][1]; + discProcessNoiseCov[0][5] = covQ2[0][2]; + discProcessNoiseCov[1][0] = covQ1[1][0]; + discProcessNoiseCov[1][1] = covQ1[1][1]; + discProcessNoiseCov[1][2] = covQ1[1][2]; + discProcessNoiseCov[1][3] = covQ2[1][0]; + discProcessNoiseCov[1][4] = covQ2[1][1]; + discProcessNoiseCov[1][5] = covQ2[1][2]; + discProcessNoiseCov[2][0] = covQ1[2][0]; + discProcessNoiseCov[2][1] = covQ1[2][1]; + discProcessNoiseCov[2][2] = covQ1[2][2]; + discProcessNoiseCov[2][3] = covQ2[2][0]; + discProcessNoiseCov[2][4] = covQ2[2][1]; + discProcessNoiseCov[2][5] = covQ2[2][2]; + discProcessNoiseCov[3][0] = transCovQ2[0][0]; + discProcessNoiseCov[3][1] = transCovQ2[0][1]; + discProcessNoiseCov[3][2] = transCovQ2[0][2]; + discProcessNoiseCov[3][3] = covQ3[0][0]; + discProcessNoiseCov[3][4] = covQ3[0][1]; + discProcessNoiseCov[3][5] = covQ3[0][2]; + discProcessNoiseCov[4][0] = transCovQ2[1][0]; + discProcessNoiseCov[4][1] = transCovQ2[1][1]; + discProcessNoiseCov[4][2] = transCovQ2[1][2]; + discProcessNoiseCov[4][3] = covQ3[1][0]; + discProcessNoiseCov[4][4] = covQ3[1][1]; + discProcessNoiseCov[4][5] = covQ3[1][2]; + discProcessNoiseCov[5][0] = transCovQ2[2][0]; + discProcessNoiseCov[5][1] = transCovQ2[2][1]; + discProcessNoiseCov[5][2] = transCovQ2[2][2]; + discProcessNoiseCov[5][3] = covQ3[2][0]; + discProcessNoiseCov[5][4] = covQ3[2][1]; + discProcessNoiseCov[5][5] = covQ3[2][2]; + } else { + // double fact1 = sampleTime*pow(sigmaV,2); + double covQ11[3][3], covQ12[3][3], covQ13[3][3]; + // MatrixOperations::multiplyScalar(*identityMatrix3, fact1, *covQ1, 3, 3); + double fact1 = (2 * normRotEst + sampleTime - 2 * sin(normRotEst * sampleTime) - + pow(normRotEst, 3) / 3 * pow(sampleTime, 3)) / + pow(normRotEst, 5); + MatrixOperations::multiply(*crossRotEst, *crossRotEst, *covQ11, 3, 3, 3); + MatrixOperations::multiplyScalar(*covQ11, fact1, *covQ11, 3, 3); + double fact2 = pow(sampleTime, 3); + MatrixOperations::multiplyScalar(*identityMatrix3, fact2, *covQ12, 3, 3); + MatrixOperations::subtract(*covQ12, *covQ11, *covQ11, 3, 3); + double fact3 = sampleTime * pow(sigmaV, 2); + MatrixOperations::multiplyScalar(*identityMatrix3, fact3, *covQ13, 3, 3); + MatrixOperations::add(*covQ13, *covQ11, *covQ1, 3, 3); + + double covQ21[3][3], covQ22[3][3], covQ23[3][3]; + double fact4 = + (0.5 * pow(normRotEst, 2) * pow(sampleTime, 2) + cos(normRotEst * sampleTime) - 1) / + pow(normRotEst, 4); + MatrixOperations::multiply(*crossRotEst, *crossRotEst, *covQ21, 3, 3, 3); + MatrixOperations::multiplyScalar(*covQ21, fact4, *covQ21, 3, 3); + double fact5 = 0.5 * pow(sampleTime, 2); + MatrixOperations::multiplyScalar(*identityMatrix3, fact5, *covQ22, 3, 3); + MatrixOperations::add(*covQ22, *covQ21, *covQ21, 3, 3); + double fact6 = normRotEst * sampleTime - sin(normRotEst * sampleTime) / pow(normRotEst, 3); + MatrixOperations::multiplyScalar(*crossRotEst, fact6, *covQ23, 3, 3); + MatrixOperations::subtract(*covQ23, *covQ21, *covQ21, 3, 3); + double fact7 = pow(sigmaU, 2); + MatrixOperations::multiplyScalar(*covQ21, fact7, *covQ2, 3, 3); + + MatrixOperations::multiplyScalar(*identityMatrix3, fact7, *covQ3, 3, 3); + + discProcessNoiseCov[0][0] = covQ1[0][0]; + discProcessNoiseCov[0][1] = covQ1[0][1]; + discProcessNoiseCov[0][2] = covQ1[0][2]; + discProcessNoiseCov[0][3] = covQ2[0][0]; + discProcessNoiseCov[0][4] = covQ2[0][1]; + discProcessNoiseCov[0][5] = covQ2[0][2]; + discProcessNoiseCov[1][0] = covQ1[1][0]; + discProcessNoiseCov[1][1] = covQ1[1][1]; + discProcessNoiseCov[1][2] = covQ1[1][2]; + discProcessNoiseCov[1][3] = covQ2[1][0]; + discProcessNoiseCov[1][4] = covQ2[1][1]; + discProcessNoiseCov[1][5] = covQ2[1][2]; + discProcessNoiseCov[2][0] = covQ1[2][0]; + discProcessNoiseCov[2][1] = covQ1[2][1]; + discProcessNoiseCov[2][2] = covQ1[2][2]; + discProcessNoiseCov[2][3] = covQ2[2][0]; + discProcessNoiseCov[2][4] = covQ2[2][1]; + discProcessNoiseCov[2][5] = covQ2[2][2]; + discProcessNoiseCov[3][0] = covQ2[0][0]; + discProcessNoiseCov[3][1] = covQ2[0][1]; + discProcessNoiseCov[3][2] = covQ2[0][2]; + discProcessNoiseCov[3][3] = covQ3[0][0]; + discProcessNoiseCov[3][4] = covQ3[0][1]; + discProcessNoiseCov[3][5] = covQ3[0][2]; + discProcessNoiseCov[4][0] = covQ2[1][0]; + discProcessNoiseCov[4][1] = covQ2[1][1]; + discProcessNoiseCov[4][2] = covQ2[1][2]; + discProcessNoiseCov[4][3] = covQ3[1][0]; + discProcessNoiseCov[4][4] = covQ3[1][1]; + discProcessNoiseCov[4][5] = covQ3[1][2]; + discProcessNoiseCov[5][0] = covQ2[2][0]; + discProcessNoiseCov[5][1] = covQ2[2][1]; + discProcessNoiseCov[5][2] = covQ2[2][2]; + discProcessNoiseCov[5][3] = covQ3[2][0]; + discProcessNoiseCov[5][4] = covQ3[2][1]; + discProcessNoiseCov[5][5] = covQ3[2][2]; + } + + // State Transition Matrix phi + double phi1[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, + phi2[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}, + 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[3][3], phi12[3][3]; + double fact1 = sin(normRotEst * sampleTime); + MatrixOperations::multiplyScalar(*crossRotEst, fact1, *phi11, 3, 3); + double fact2 = (1 - cos(normRotEst * sampleTime)) / pow(normRotEst, 2); + MatrixOperations::multiply(*crossRotEst, *crossRotEst, *phi12, 3, 3, 3); + MatrixOperations::multiplyScalar(*phi12, fact2, *phi12, 3, 3); + MatrixOperations::subtract(*identityMatrix3, *phi11, *phi11, 3, 3); + MatrixOperations::add(*phi11, *phi12, *phi1, 3, 3); + + double phi21[3][3], phi22[3][3]; + MatrixOperations::multiplyScalar(*crossRotEst, fact2, *phi21, 3, 3); + MatrixOperations::multiplyScalar(*identityMatrix3, sampleTime, *phi22, 3, 3); + MatrixOperations::subtract(*phi21, *phi22, *phi21, 3, 3); + double fact3 = (normRotEst * sampleTime - sin(normRotEst * sampleTime) / pow(normRotEst, 3)); + MatrixOperations::multiply(*crossRotEst, *crossRotEst, *phi22, 3, 3, 3); + MatrixOperations::multiplyScalar(*phi22, fact3, *phi22, 3, 3); + MatrixOperations::subtract(*phi21, *phi22, *phi2, 3, 3); + + phi[0][0] = phi1[0][0]; + phi[0][1] = phi1[0][1]; + phi[0][2] = phi1[0][2]; + phi[0][3] = phi2[0][0]; + phi[0][4] = phi2[0][1]; + phi[0][5] = phi2[0][2]; + phi[1][0] = phi1[1][0]; + phi[1][1] = phi1[1][1]; + phi[1][2] = phi1[1][2]; + phi[1][3] = phi2[1][0]; + phi[1][4] = phi2[1][1]; + phi[1][5] = phi2[1][2]; + phi[2][0] = phi1[2][0]; + phi[2][1] = phi1[2][1]; + phi[2][2] = phi1[2][2]; + phi[2][3] = phi2[2][0]; + phi[2][4] = phi2[2][1]; + phi[2][5] = phi2[2][2]; + + // Propagated Quaternion + double rotSin[3] = {0, 0, 0}, omega1[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; + VectorOperations::mulScalar(rotRateEst, sinFac, rotSin, 3); + + double skewSin[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MathOperations::skewMatrix(rotSin, *skewSin); + + MatrixOperations::multiplyScalar(*identityMatrix3, rotCos, *omega1, 3, 3); + MatrixOperations::subtract(*omega1, *skewSin, *omega1, 3, 3); + double omega[4][4] = {{omega1[0][0], omega1[0][1], omega1[0][2], rotSin[0]}, + {omega1[1][0], omega1[1][1], omega1[1][2], rotSin[1]}, + {omega1[2][0], omega1[2][1], omega1[2][2], rotSin[2]}, + {-rotSin[0], -rotSin[1], -rotSin[2], rotCos}}; + MatrixOperations::multiply(*omega, quatBJ, propagatedQuaternion, 4, 4, 1); + + // Update Covariance Matrix + double cov1[6][6], cov2[6][6], transDiscTimeMatrix[6][6], transPhi[6][6]; + MatrixOperations::transpose(*discTimeMatrix, *transDiscTimeMatrix, 6); + MatrixOperations::multiply(*discProcessNoiseCov, *transDiscTimeMatrix, *cov1, 6, 6, 6); + MatrixOperations::multiply(*discTimeMatrix, *cov1, *cov1, 6, 6, 6); + + MatrixOperations::transpose(*phi, *transPhi, 6); + MatrixOperations::multiply(*covMatPlus, *transPhi, *cov2, 6, 6, 6); + MatrixOperations::multiply(*phi, *cov2, *cov2, 6, 6, 6); + + MatrixOperations::add(*cov2, *cov1, *initialCovarianceMatrix, 6, 6); + validMekf = true; + + // Discrete Time Step + + // Check for new data in measurement -> SensorProcessing ? + + return returnvalue::OK; } diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.h b/mission/controller/acs/MultiplicativeKalmanFilter.h index 542db996..f1d2d7a0 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.h +++ b/mission/controller/acs/MultiplicativeKalmanFilter.h @@ -7,101 +7,95 @@ * @brief: This class handles the calculation of an estimated quaternion and the gyro bias by * means of the spacecraft attitude sensors * - * @note: A description of the used algorithms can be found in the bachelor thesis of Robin Marquardt + * @note: A description of the used algorithms can be found in the bachelor thesis of Robin + * Marquardt * https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_Studenten/Marquardt_Robin&openfile=500811 */ #ifndef MULTIPLICATIVEKALMANFILTER_H_ #define MULTIPLICATIVEKALMANFILTER_H_ +#include //uint8_t +#include /*purpose, timeval ?*/ + #include "config/classIds.h" -#include //uint8_t -#include /*purpose, timeval ?*/ //#include <_timeval.h> #include "AcsParameters.h" -class MultiplicativeKalmanFilter{ -public: - /* @brief: Constructor - * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters - */ - MultiplicativeKalmanFilter(AcsParameters *acsParameters_); - virtual ~MultiplicativeKalmanFilter(); +class MultiplicativeKalmanFilter { + public: + /* @brief: Constructor + * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters + */ + MultiplicativeKalmanFilter(AcsParameters *acsParameters_); + virtual ~MultiplicativeKalmanFilter(); - void reset(); // NOT YET DEFINED - should only reset all mekf variables + void reset(); // NOT YET DEFINED - should only reset all mekf variables - /* @brief: init() - This function initializes the Kalman Filter and will provide the first quaternion through - * the QUEST algorithm - * @param: magneticField_ magnetic field vector in the body frame - * sunDir_ sun direction vector in the body frame - * sunDirJ sun direction vector in the ECI frame - * magFieldJ magnetic field vector in the ECI frame - */ - void 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); + /* @brief: init() - This function initializes the Kalman Filter and will provide the first + * quaternion through the QUEST algorithm + * @param: magneticField_ magnetic field vector in the body frame + * sunDir_ sun direction vector in the body frame + * sunDirJ sun direction vector in the ECI frame + * magFieldJ magnetic field vector in the ECI frame + */ + void 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); - /* @brief: mekfEst() - This function calculates the quaternion and gyro bias of the Kalman Filter for the current step - * after the initalization - * @param: quaternionSTR Star Tracker Quaternion between from body to ECI frame - * rateRMUs_ Estimated satellite rotation rate from the Rate Measurement Units [rad/s] - * magneticField_ magnetic field vector in the body frame - * sunDir_ sun direction vector in the body frame - * sunDirJ sun direction vector in the ECI frame - * magFieldJ magnetic field vector in the ECI frame - * outputQuat Stores the calculated quaternion - * outputSatRate Stores the adjusted satellite rate - * @return ReturnValue_t Feedback of this class, KALMAN_NO_RMU_MEAS if no satellite rate from the sensors was provided, - * KALMAN_NO_MODEL if no sunDirJ or magFieldJ was given from the model calculations, - * KALMAN_INVERSION_FAILED if the calculation of the Gain matrix was not possible, - * RETURN_OK else - */ - ReturnValue_t mekfEst( - const double *quaternionSTR, const bool *validSTR_, - const double *rateRMUs_, const bool *validRMUs_, - 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 *outputQuat, double *outputSatRate); + /* @brief: mekfEst() - This function calculates the quaternion and gyro bias of the Kalman Filter + * for the current step after the initalization + * @param: quaternionSTR Star Tracker Quaternion between from body to ECI frame + * rateGYRs_ Estimated satellite rotation rate from the + * Gyroscopes [rad/s] magneticField_ magnetic field vector in the body frame sunDir_ + * sun direction vector in the body frame sunDirJ sun direction vector in the ECI + * frame magFieldJ magnetic field vector in the ECI frame + * outputQuat Stores the calculated quaternion + * outputSatRate Stores the adjusted satellite rate + * @return ReturnValue_t Feedback of this class, KALMAN_NO_GYR_MEAS if no satellite rate from + * the sensors was provided, KALMAN_NO_MODEL if no sunDirJ or magFieldJ was given from the model + * calculations, KALMAN_INVERSION_FAILED if the calculation of the Gain matrix was not possible, + * RETURN_OK else + */ + ReturnValue_t 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 *outputQuat, double *outputSatRate); + // Declaration of Events (like init) and memberships + // static const uint8_t INTERFACE_ID = CLASS_ID::MEKF; //CLASS IDS ND + // (/config/returnvalues/classIDs.h) static const Event RESET = + // MAKE_EVENT(1,severity::INFO);//typedef uint32_t Event (Event.h), should be + // resetting Mekf + static const uint8_t INTERFACE_ID = CLASS_ID::KALMAN; + static const ReturnValue_t KALMAN_NO_GYR_MEAS = MAKE_RETURN_CODE(0x01); + static const ReturnValue_t KALMAN_NO_MODEL = MAKE_RETURN_CODE(0x02); + static const ReturnValue_t KALMAN_INVERSION_FAILED = MAKE_RETURN_CODE(0x03); - // Declaration of Events (like init) and memberships - //static const uint8_t INTERFACE_ID = CLASS_ID::MEKF; //CLASS IDS ND (/config/returnvalues/classIDs.h) - //static const Event RESET = MAKE_EVENT(1,severity::INFO);//typedef uint32_t Event (Event.h), should be - // resetting Mekf - static const uint8_t INTERFACE_ID = CLASS_ID::KALMAN; - static const ReturnValue_t KALMAN_NO_RMU_MEAS = MAKE_RETURN_CODE(0x01); - static const ReturnValue_t KALMAN_NO_MODEL = MAKE_RETURN_CODE(0x02); - static const ReturnValue_t KALMAN_INVERSION_FAILED = MAKE_RETURN_CODE(0x03); + private: + /*Parameters*/ + AcsParameters::InertiaEIVE *inertiaEIVE; + AcsParameters::KalmanFilterParameters *kalmanFilterParameters; + double quaternion_STR_SB[4]; + bool validInit; + double sampleTime = 0.1; -private: -/*Parameters*/ - AcsParameters::InertiaEIVE* inertiaEIVE; - AcsParameters::KalmanFilterParameters* kalmanFilterParameters; - double quaternion_STR_SB[4]; - bool validInit; - double sampleTime = 0.1; + /*States*/ + double initialQuaternion[4]; /*after reset?QUEST*/ + double initialCovarianceMatrix[6][6]; /*after reset?QUEST*/ + double propagatedQuaternion[4]; /*Filter Quaternion for next step*/ + bool validMekf; + uint8_t sensorsAvail; - -/*States*/ - double initialQuaternion[4]; /*after reset?QUEST*/ - double initialCovarianceMatrix[6][6];/*after reset?QUEST*/ - double propagatedQuaternion[4]; /*Filter Quaternion for next step*/ - bool validMekf; - uint8_t sensorsAvail; - -/*Outputs*/ - double quatBJ[4]; /* Output Quaternion */ - double biasRMU[3]; /*Between measured and estimated sat Rate*/ -/*Parameter INIT*/ - //double alpha, gamma, beta; -/*Functions*/ - void loadAcsParameters(AcsParameters *acsParameters_); + /*Outputs*/ + double quatBJ[4]; /* Output Quaternion */ + double biasGYR[3]; /*Between measured and estimated sat Rate*/ + /*Parameter INIT*/ + // double alpha, gamma, beta; + /*Functions*/ + void loadAcsParameters(AcsParameters *acsParameters_); }; - - #endif /* ACS_MULTIPLICATIVEKALMANFILTER_H_ */ diff --git a/mission/controller/acs/Navigation.cpp b/mission/controller/acs/Navigation.cpp index deb50aa1..2c1596e5 100644 --- a/mission/controller/acs/Navigation.cpp +++ b/mission/controller/acs/Navigation.cpp @@ -36,8 +36,7 @@ void Navigation::useMekf(ACS::SensorValues *sensorValues, ACS::OutputValues *out &outputValues->sunDirEstValid, outputValues->sunDirModel, &outputValues->sunDirModelValid, outputValues->magFieldModel, &outputValues->magFieldModelValid, outputValues->quatMekfBJ, outputValues->satRateMekf); // VALIDS FOR QUAT AND RATE ?? - } - else { + } else { multiplicativeKalmanFilter.init(outputValues->magFieldEst, &outputValues->magFieldEstValid, outputValues->sunDirEst, &outputValues->sunDirEstValid, outputValues->sunDirModel, &outputValues->sunDirModelValid, @@ -45,7 +44,8 @@ void Navigation::useMekf(ACS::SensorValues *sensorValues, ACS::OutputValues *out kalmanInit = true; *mekfValid = 0; - // Maybe we need feedback from kalmanfilter to identify if there was a problem with the init - //of kalman filter where does this class know from that kalman filter was not initialized ? + // Maybe we need feedback from kalmanfilter to identify if there was a problem with the + // init of kalman filter where does this class know from that kalman filter was not + // initialized ? } } diff --git a/mission/controller/acs/control/PtgCtrl.cpp b/mission/controller/acs/control/PtgCtrl.cpp index 6201a32a..7160fb47 100644 --- a/mission/controller/acs/control/PtgCtrl.cpp +++ b/mission/controller/acs/control/PtgCtrl.cpp @@ -123,7 +123,7 @@ void PtgCtrl::ptgDesaturation(double *magFieldEst, bool *magFieldEstValid, doubl } // calculating momentum of satellite and momentum of reaction wheels - double speedRws[4] = {*speedRw0, *speedRw1, *speedRw2, *speedRw3}; + 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, @@ -145,7 +145,7 @@ void PtgCtrl::ptgDesaturation(double *magFieldEst, bool *magFieldEstValid, doubl void PtgCtrl::ptgNullspace(const int32_t *speedRw0, const int32_t *speedRw1, const int32_t *speedRw2, const int32_t *speedRw3, double *rwTrqNs) { - double speedRws[4] = {*speedRw0, *speedRw1, *speedRw2, *speedRw3}; + 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 -- 2.34.1 From 4bd2a2dac847ddde2037ebddf70a8c29a55552ff Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 24 Oct 2022 10:41:28 +0200 Subject: [PATCH 074/101] added and implemented all ACS related DataPools to AcsController --- mission/controller/AcsController.cpp | 311 ++++++++++++++---- mission/controller/AcsController.h | 128 ++++--- mission/controller/acs/OutputValues.cpp | 16 +- mission/controller/acs/OutputValues.h | 63 ++-- .../AcsCtrlDefinitions.h | 5 +- 5 files changed, 352 insertions(+), 171 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 22c871fd..b42d9c83 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -12,8 +12,15 @@ AcsController::AcsController(object_id_t objectId) detumble(&acsParameters), ptgCtrl(&acsParameters), detumbleCounter{0}, - mgmData(this), - susData(this) {} + mgmDataRaw(this), + mgmDataProcessed(this), + susDataRaw(this), + susDataProcessed(this), + gyrDataRaw(this), + gyrDataProcessed(this), + gpsDataProcessed(this), + mekfData(this), + actuatorCmdData(this) {} ReturnValue_t AcsController::handleCommandMessage(CommandMessage *message) { return returnvalue::OK; @@ -38,11 +45,9 @@ void AcsController::performControlOperation() { case SUBMODE_SAFE: performSafe(); break; - case SUBMODE_DETUMBLE: performDetumble(); break; - case SUBMODE_PTG_GS: performPointingCtrl(); break; @@ -55,17 +60,23 @@ void AcsController::performControlOperation() { } { - PoolReadGuard pg(&mgmData); + PoolReadGuard pg(&mgmDataRaw); if (pg.getReadResult() == returnvalue::OK) { copyMgmData(); } } { - PoolReadGuard pg(&susData); + PoolReadGuard pg(&susDataRaw); if (pg.getReadResult() == returnvalue::OK) { copySusData(); } } + { + PoolReadGuard pg(&gyrDataRaw); + if (pg.getReadResult() == returnvalue::OK) { + copyGyrData(); + } + } // DEBUG : REMOVE AFTER COMPLETION mode = MODE_ON; @@ -81,10 +92,13 @@ void AcsController::performSafe() { ACS::SensorValues sensorValues; ACS::OutputValues outputValues; - timeval now; // We need to give the actual time here + timeval now; + Clock::getClock_timeval(&now); + sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); ReturnValue_t validMekf; navigation.useMekf(&sensorValues, &outputValues, &validMekf); // DOES THIS WORK WITH VALID? + // Give desired satellite rate and sun direction to align double satRateSafe[3] = {0, 0, 0}, sunTargetDir[3] = {0, 0, 0}; guidance.getTargetParamsSafe(sunTargetDir, satRateSafe); @@ -140,10 +154,12 @@ void AcsController::performDetumble() { timeval now; Clock::getClock_timeval(&now); + // Clock::getUptime(&now); sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); ReturnValue_t validMekf; navigation.useMekf(&sensorValues, &outputValues, &validMekf); + double magMomMtq[3] = {0, 0, 0}; detumble.bDotLaw(outputValues.magneticFieldVectorDerivative, &outputValues.magneticFieldVectorDerivativeValid, outputValues.magFieldEst, @@ -172,11 +188,13 @@ void AcsController::performPointingCtrl() { ACS::SensorValues sensorValues; ACS::OutputValues outputValues; - timeval now; // Übergabe ? + timeval now; + Clock::getClock_timeval(&now); sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); ReturnValue_t validMekf; navigation.useMekf(&sensorValues, &outputValues, &validMekf); + double targetQuat[4] = {0, 0, 0, 0}, refSatRate[3] = {0, 0, 0}; guidance.targetQuatPtg(&sensorValues, &outputValues, now, targetQuat, refSatRate); double quatError[3] = {0, 0, 0}, deltaRate[3] = {0, 0, 0}; @@ -204,38 +222,106 @@ void AcsController::performPointingCtrl() { ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { - // MGM - localDataPoolMap.emplace(acsctrl::PoolIds::MGM_0_LIS3_UT, &mgm0PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::MGM_1_RM3100_UT, &mgm1PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::MGM_2_LIS3_UT, &mgm2PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::MGM_3_RM3100_UT, &mgm3PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_NT, &imtqMgmPoolVec); + // MGM Raw + localDataPoolMap.emplace(acsctrl::PoolIds::MGM_0_LIS3_UT, &mgm0VecRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::MGM_1_RM3100_UT, &mgm1VecRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::MGM_2_LIS3_UT, &mgm2VecRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::MGM_3_RM3100_UT, &mgm3VecRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_NT, &imtqMgmVecRaw); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_ACT_STATUS, &imtqCalActStatus); - poolManager.subscribeForRegularPeriodicPacket({mgmData.getSid(), false, 5.0}); - // SUS - localDataPoolMap.emplace(acsctrl::PoolIds::SUS_0_N_LOC_XFYFZM_PT_XF, &sus0PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::SUS_1_N_LOC_XBYFZM_PT_XB, &sus1PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::SUS_2_N_LOC_XFYBZB_PT_YB, &sus2PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::SUS_3_N_LOC_XFYBZF_PT_YF, &sus3PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::SUS_4_N_LOC_XMYFZF_PT_ZF, &sus4PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::SUS_5_N_LOC_XFYMZB_PT_ZB, &sus5PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::SUS_6_R_LOC_XFYBZM_PT_XF, &sus6PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::SUS_7_R_LOC_XBYBZM_PT_XB, &sus7PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::SUS_8_R_LOC_XBYBZB_PT_YB, &sus8PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::SUS_9_R_LOC_XBYBZB_PT_YF, &sus9PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::SUS_10_N_LOC_XMYBZF_PT_ZF, &sus10PoolVec); - localDataPoolMap.emplace(acsctrl::PoolIds::SUS_11_R_LOC_XBYMZB_PT_ZB, &sus11PoolVec); - poolManager.subscribeForRegularPeriodicPacket({susData.getSid(), false, 5.0}); + poolManager.subscribeForRegularPeriodicPacket({mgmDataRaw.getSid(), false, 5.0}); + // MGM Processed + localDataPoolMap.emplace(acsctrl::PoolIds::MGM_0_VEC, &mgm0VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::MGM_1_VEC, &mgm1VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::MGM_2_VEC, &mgm2VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::MGM_3_VEC, &mgm3VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::MGM_VEC_TOT, &mgmVecTot); + localDataPoolMap.emplace(acsctrl::PoolIds::MGM_VEC_TOT_DERIVATIVE, &mgmVecTotDer); + localDataPoolMap.emplace(acsctrl::PoolIds::MAG_IGRF_MODEL, &magIgrf); + poolManager.subscribeForRegularPeriodicPacket({mgmDataProcessed.getSid(), false, 5.0}); + // SUS Raw + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_0_N_LOC_XFYFZM_PT_XF, &sus0ValRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_1_N_LOC_XBYFZM_PT_XB, &sus1ValRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_2_N_LOC_XFYBZB_PT_YB, &sus2ValRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_3_N_LOC_XFYBZF_PT_YF, &sus3ValRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_4_N_LOC_XMYFZF_PT_ZF, &sus4ValRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_5_N_LOC_XFYMZB_PT_ZB, &sus5ValRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_6_R_LOC_XFYBZM_PT_XF, &sus6ValRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_7_R_LOC_XBYBZM_PT_XB, &sus7ValRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_8_R_LOC_XBYBZB_PT_YB, &sus8ValRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_9_R_LOC_XBYBZB_PT_YF, &sus9ValRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_10_N_LOC_XMYBZF_PT_ZF, &sus10ValRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_11_R_LOC_XBYMZB_PT_ZB, &sus11ValRaw); + poolManager.subscribeForRegularPeriodicPacket({susDataRaw.getSid(), false, 5.0}); + // SUS Processed + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_0_VEC, &sus0VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_1_VEC, &sus1VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_2_VEC, &sus2VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_3_VEC, &sus3VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_4_VEC, &sus4VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_5_VEC, &sus5VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_6_VEC, &sus6VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_7_VEC, &sus7VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_8_VEC, &sus8VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_9_VEC, &sus9VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_10_VEC, &sus10VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_11_VEC, &sus11VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_VEC_TOT, &susVecTot); + localDataPoolMap.emplace(acsctrl::PoolIds::SUS_VEC_TOT_DERIVATIVE, &susVecTotDer); + localDataPoolMap.emplace(acsctrl::PoolIds::SUN_IJK_MODEL, &sunIjk); + poolManager.subscribeForRegularPeriodicPacket({susDataProcessed.getSid(), false, 5.0}); + // GYR Raw + localDataPoolMap.emplace(acsctrl::PoolIds::GYR_0_ADIS, &gyr0VecRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::GYR_1_L3, &gyr1VecRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::GYR_2_ADIS, &gyr2VecRaw); + localDataPoolMap.emplace(acsctrl::PoolIds::GYR_3_L3, &gyr3VecRaw); + poolManager.subscribeForRegularPeriodicPacket({gyrDataRaw.getSid(), false, 5.0}); + // GYR Processed + localDataPoolMap.emplace(acsctrl::PoolIds::GYR_0_VEC, &gyr0VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::GYR_1_VEC, &gyr1VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::GYR_2_VEC, &gyr2VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::GYR_3_VEC, &gyr3VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::GYR_VEC_TOT, &gyrVecTot); + poolManager.subscribeForRegularPeriodicPacket({gyrDataProcessed.getSid(), false, 5.0}); + // GPS Processed + localDataPoolMap.emplace(acsctrl::PoolIds::GC_LATITUDE, &gcLatitude); + localDataPoolMap.emplace(acsctrl::PoolIds::GD_LONGITUDE, &gdLongitude); + poolManager.subscribeForRegularPeriodicPacket({gpsDataProcessed.getSid(), false, 5.0}); + // MEKF + localDataPoolMap.emplace(acsctrl::PoolIds::QUAT_MEKF, &quatMekf); + localDataPoolMap.emplace(acsctrl::PoolIds::SAT_ROT_RATE_MEKF, &satRotRateMekf); + poolManager.subscribeForRegularPeriodicPacket({mekfData.getSid(), false, 5.0}); + // Actuator CMD + localDataPoolMap.emplace(acsctrl::PoolIds::RW_TARGET_TORQUE, &rwTargetTorque); + localDataPoolMap.emplace(acsctrl::PoolIds::RW_TARGET_SPEED, &rwTargetSpeed); + localDataPoolMap.emplace(acsctrl::PoolIds::MTQ_TARGET_DIPOLE, &mtqTargetDipole); + poolManager.subscribeForRegularPeriodicPacket({actuatorCmdData.getSid(), false, 5.0}); return returnvalue::OK; } LocalPoolDataSetBase *AcsController::getDataSetHandle(sid_t sid) { - if (sid == mgmData.getSid()) { - return &mgmData; - } else if (sid == susData.getSid()) { - return &susData; + switch (sid.ownerSetId) { + case acsctrl::MGM_SENSOR_DATA: + return &mgmDataRaw; + case acsctrl::MGM_PROCESSED_DATA: + return &mgmDataProcessed; + case acsctrl::SUS_SENSOR_DATA: + return &susDataRaw; + case acsctrl::SUS_PROCESSED_DATA: + return &susDataProcessed; + case acsctrl::GYR_SENSOR_DATA: + return &gyrDataRaw; + case acsctrl::GYR_PROCESSED_DATA: + return &gyrDataProcessed; + case acsctrl::GPS_PROCESSED_DATA: + return &gpsDataProcessed; + case acsctrl::MEKF_DATA: + return &mekfData; + case acsctrl::ACTUATOR_CMD_DATA: + return &actuatorCmdData; + default: + return nullptr; } - return nullptr; } ReturnValue_t AcsController::checkModeCommand(Mode_t mode, Submode_t submode, @@ -261,112 +347,195 @@ void AcsController::modeChanged(Mode_t mode, Submode_t submode) {} void AcsController::announceMode(bool recursive) {} void AcsController::copyMgmData() { + ACS::SensorValues sensorValues; { - PoolReadGuard pg(&mgm0Lis3Set); + PoolReadGuard pg(&sensorValues.mgm0Lis3Set); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(mgmData.mgm0Lis3.value, mgm0Lis3Set.fieldStrengths.value, 3 * sizeof(float)); + std::memcpy(mgmDataRaw.mgm0Lis3.value, sensorValues.mgm0Lis3Set.fieldStrengths.value, + 3 * sizeof(float)); + mgmDataRaw.mgm0Lis3.setValid(sensorValues.mgm0Lis3Set.fieldStrengths.isValid()); } } { - PoolReadGuard pg(&mgm1Rm3100Set); + PoolReadGuard pg(&sensorValues.mgm1Rm3100Set); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(mgmData.mgm1Rm3100.value, mgm1Rm3100Set.fieldStrengths.value, 3 * sizeof(float)); + std::memcpy(mgmDataRaw.mgm1Rm3100.value, sensorValues.mgm1Rm3100Set.fieldStrengths.value, + 3 * sizeof(float)); + mgmDataRaw.mgm1Rm3100.setValid(sensorValues.mgm1Rm3100Set.fieldStrengths.isValid()); } } { - PoolReadGuard pg(&mgm2Lis3Set); + PoolReadGuard pg(&sensorValues.mgm2Lis3Set); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(mgmData.mgm2Lis3.value, mgm2Lis3Set.fieldStrengths.value, 3 * sizeof(float)); + std::memcpy(mgmDataRaw.mgm2Lis3.value, sensorValues.mgm2Lis3Set.fieldStrengths.value, + 3 * sizeof(float)); + mgmDataRaw.mgm2Lis3.setValid(sensorValues.mgm2Lis3Set.fieldStrengths.isValid()); } } { - PoolReadGuard pg(&mgm3Rm3100Set); + PoolReadGuard pg(&sensorValues.mgm3Rm3100Set); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(mgmData.mgm3Rm3100.value, mgm3Rm3100Set.fieldStrengths.value, 3 * sizeof(float)); + std::memcpy(mgmDataRaw.mgm3Rm3100.value, sensorValues.mgm3Rm3100Set.fieldStrengths.value, + 3 + sizeof(float)); + mgmDataRaw.mgm3Rm3100.setValid(sensorValues.mgm3Rm3100Set.fieldStrengths.isValid()); } } { - PoolReadGuard pg(&imtqMgmSet); + PoolReadGuard pg(&sensorValues.imtqMgmSet); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(mgmData.imtqRaw.value, imtqMgmSet.mtmRawNt.value, 3 * sizeof(float)); - mgmData.actuationCalStatus.value = imtqMgmSet.coilActuationStatus.value; + std::memcpy(mgmDataRaw.imtqRaw.value, sensorValues.imtqMgmSet.mtmRawNt.value, + 3 * sizeof(float)); + mgmDataRaw.imtqRaw.setValid(sensorValues.imtqMgmSet.mtmRawNt.isValid()); + mgmDataRaw.actuationCalStatus.value = sensorValues.imtqMgmSet.coilActuationStatus.value; + mgmDataRaw.actuationCalStatus.setValid(sensorValues.imtqMgmSet.coilActuationStatus.isValid()); } } } void AcsController::copySusData() { + ACS::SensorValues sensorValues; { - PoolReadGuard pg(&susSets[0]); + PoolReadGuard pg(&sensorValues.susSets[0]); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(susData.sus0.value, susSets[0].channels.value, 6 * sizeof(uint16_t)); + std::memcpy(susDataRaw.sus0.value, sensorValues.susSets[0].channels.value, + 6 * sizeof(uint16_t)); + susDataRaw.sus0.setValid(sensorValues.susSets[0].channels.isValid()); } } { - PoolReadGuard pg(&susSets[1]); + PoolReadGuard pg(&sensorValues.susSets[1]); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(susData.sus1.value, susSets[1].channels.value, 6 * sizeof(uint16_t)); + std::memcpy(susDataRaw.sus1.value, sensorValues.susSets[1].channels.value, + 6 * sizeof(uint16_t)); + susDataRaw.sus1.setValid(sensorValues.susSets[1].channels.isValid()); } } { - PoolReadGuard pg(&susSets[2]); + PoolReadGuard pg(&sensorValues.susSets[2]); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(susData.sus2.value, susSets[2].channels.value, 6 * sizeof(uint16_t)); + std::memcpy(susDataRaw.sus2.value, sensorValues.susSets[2].channels.value, + 6 * sizeof(uint16_t)); + susDataRaw.sus2.setValid(sensorValues.susSets[2].channels.isValid()); } } { - PoolReadGuard pg(&susSets[3]); + PoolReadGuard pg(&sensorValues.susSets[3]); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(susData.sus3.value, susSets[3].channels.value, 6 * sizeof(uint16_t)); + std::memcpy(susDataRaw.sus3.value, sensorValues.susSets[3].channels.value, + 6 * sizeof(uint16_t)); + susDataRaw.sus3.setValid(sensorValues.susSets[3].channels.isValid()); } } { - PoolReadGuard pg(&susSets[4]); + PoolReadGuard pg(&sensorValues.susSets[4]); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(susData.sus4.value, susSets[4].channels.value, 6 * sizeof(uint16_t)); + std::memcpy(susDataRaw.sus4.value, sensorValues.susSets[4].channels.value, + 6 * sizeof(uint16_t)); + susDataRaw.sus4.setValid(sensorValues.susSets[4].channels.isValid()); } } { - PoolReadGuard pg(&susSets[5]); + PoolReadGuard pg(&sensorValues.susSets[5]); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(susData.sus5.value, susSets[5].channels.value, 6 * sizeof(uint16_t)); + std::memcpy(susDataRaw.sus5.value, sensorValues.susSets[5].channels.value, + 6 * sizeof(uint16_t)); + susDataRaw.sus5.setValid(sensorValues.susSets[5].channels.isValid()); } } { - PoolReadGuard pg(&susSets[6]); + PoolReadGuard pg(&sensorValues.susSets[6]); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(susData.sus6.value, susSets[6].channels.value, 6 * sizeof(uint16_t)); + std::memcpy(susDataRaw.sus6.value, sensorValues.susSets[6].channels.value, + 6 * sizeof(uint16_t)); + susDataRaw.sus6.setValid(sensorValues.susSets[6].channels.isValid()); } } { - PoolReadGuard pg(&susSets[7]); + PoolReadGuard pg(&sensorValues.susSets[7]); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(susData.sus7.value, susSets[7].channels.value, 6 * sizeof(uint16_t)); + std::memcpy(susDataRaw.sus7.value, sensorValues.susSets[7].channels.value, + 6 * sizeof(uint16_t)); + susDataRaw.sus7.setValid(sensorValues.susSets[7].channels.isValid()); } } { - PoolReadGuard pg(&susSets[8]); + PoolReadGuard pg(&sensorValues.susSets[8]); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(susData.sus8.value, susSets[8].channels.value, 6 * sizeof(uint16_t)); + std::memcpy(susDataRaw.sus8.value, sensorValues.susSets[8].channels.value, + 6 * sizeof(uint16_t)); + susDataRaw.sus8.setValid(sensorValues.susSets[8].channels.isValid()); } } { - PoolReadGuard pg(&susSets[9]); + PoolReadGuard pg(&sensorValues.susSets[9]); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(susData.sus9.value, susSets[9].channels.value, 6 * sizeof(uint16_t)); - sif::debug << susData.sus9.isValid() << std::endl; - sif::debug << susSets[9].channels.isValid() << std::endl; + std::memcpy(susDataRaw.sus9.value, sensorValues.susSets[9].channels.value, + 6 * sizeof(uint16_t)); + susDataRaw.sus9.setValid(sensorValues.susSets[9].channels.isValid()); } } { - PoolReadGuard pg(&susSets[10]); + PoolReadGuard pg(&sensorValues.susSets[10]); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(susData.sus10.value, susSets[10].channels.value, 6 * sizeof(uint16_t)); + std::memcpy(susDataRaw.sus10.value, sensorValues.susSets[10].channels.value, + 6 * sizeof(uint16_t)); + susDataRaw.sus10.setValid(sensorValues.susSets[10].channels.isValid()); } } { - PoolReadGuard pg(&susSets[11]); + PoolReadGuard pg(&sensorValues.susSets[11]); if (pg.getReadResult() == returnvalue::OK) { - std::memcpy(susData.sus11.value, susSets[11].channels.value, 6 * sizeof(uint16_t)); + std::memcpy(susDataRaw.sus11.value, sensorValues.susSets[11].channels.value, + 6 * sizeof(uint16_t)); + susDataRaw.sus11.setValid(sensorValues.susSets[11].channels.isValid()); + } + } +} + +void AcsController::copyGyrData() { + ACS::SensorValues sensorValues; + { + PoolReadGuard pg(&sensorValues.gyr0AdisSet); + if (pg.getReadResult() == returnvalue::OK) { + gyrDataRaw.gyr0Adis.value[0] = sensorValues.gyr0AdisSet.angVelocX.value; + gyrDataRaw.gyr0Adis.value[1] = sensorValues.gyr0AdisSet.angVelocY.value; + gyrDataRaw.gyr0Adis.value[2] = sensorValues.gyr0AdisSet.angVelocZ.value; + gyrDataRaw.gyr0Adis.setValid(sensorValues.gyr0AdisSet.angVelocX.isValid() && + sensorValues.gyr0AdisSet.angVelocY.isValid() && + sensorValues.gyr0AdisSet.angVelocZ.isValid()); + } + } + { + PoolReadGuard pg(&sensorValues.gyr1L3gSet); + if (pg.getReadResult() == returnvalue::OK) { + gyrDataRaw.gyr1L3.value[0] = sensorValues.gyr1L3gSet.angVelocX.value; + gyrDataRaw.gyr1L3.value[1] = sensorValues.gyr1L3gSet.angVelocY.value; + gyrDataRaw.gyr1L3.value[2] = sensorValues.gyr1L3gSet.angVelocZ.value; + gyrDataRaw.gyr1L3.setValid(sensorValues.gyr1L3gSet.angVelocX.isValid() && + sensorValues.gyr1L3gSet.angVelocY.isValid() && + sensorValues.gyr1L3gSet.angVelocZ.isValid()); + } + } + { + PoolReadGuard pg(&sensorValues.gyr2AdisSet); + if (pg.getReadResult() == returnvalue::OK) { + gyrDataRaw.gyr2Adis.value[0] = sensorValues.gyr2AdisSet.angVelocX.value; + gyrDataRaw.gyr2Adis.value[1] = sensorValues.gyr2AdisSet.angVelocY.value; + gyrDataRaw.gyr2Adis.value[2] = sensorValues.gyr2AdisSet.angVelocZ.value; + gyrDataRaw.gyr2Adis.setValid(sensorValues.gyr2AdisSet.angVelocX.isValid() && + sensorValues.gyr2AdisSet.angVelocY.isValid() && + sensorValues.gyr2AdisSet.angVelocZ.isValid()); + } + } + { + PoolReadGuard pg(&sensorValues.gyr3L3gSet); + if (pg.getReadResult() == returnvalue::OK) { + gyrDataRaw.gyr3L3.value[0] = sensorValues.gyr3L3gSet.angVelocX.value; + gyrDataRaw.gyr3L3.value[1] = sensorValues.gyr3L3gSet.angVelocY.value; + gyrDataRaw.gyr3L3.value[2] = sensorValues.gyr3L3gSet.angVelocZ.value; + gyrDataRaw.gyr3L3.setValid(sensorValues.gyr3L3gSet.angVelocX.isValid() && + sensorValues.gyr3L3gSet.angVelocY.isValid() && + sensorValues.gyr3L3gSet.angVelocZ.isValid()); } } } diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index a8ae9daa..87aaf37c 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -8,6 +8,7 @@ #include "acs/ActuatorCmd.h" #include "acs/Guidance.h" #include "acs/Navigation.h" +#include "acs/OutputValues.h" #include "acs/SensorProcessing.h" #include "acs/control/Detumble.h" #include "acs/control/PtgCtrl.h" @@ -64,62 +65,91 @@ class AcsController : public ExtendedControllerBase { void modeChanged(Mode_t mode, Submode_t submode); void announceMode(bool recursive); + /* ACS Datasets */ // MGMs - acsctrl::MgmDataRaw mgmData; - - MGMLIS3MDL::MgmPrimaryDataset mgm0Lis3Set = - MGMLIS3MDL::MgmPrimaryDataset(objects::MGM_0_LIS3_HANDLER); - RM3100::Rm3100PrimaryDataset mgm1Rm3100Set = - RM3100::Rm3100PrimaryDataset(objects::MGM_1_RM3100_HANDLER); - MGMLIS3MDL::MgmPrimaryDataset mgm2Lis3Set = - MGMLIS3MDL::MgmPrimaryDataset(objects::MGM_2_LIS3_HANDLER); - RM3100::Rm3100PrimaryDataset mgm3Rm3100Set = - RM3100::Rm3100PrimaryDataset(objects::MGM_3_RM3100_HANDLER); - IMTQ::RawMtmMeasurementSet imtqMgmSet = IMTQ::RawMtmMeasurementSet(objects::IMTQ_HANDLER); - - PoolEntry mgm0PoolVec = PoolEntry(3); - PoolEntry mgm1PoolVec = PoolEntry(3); - PoolEntry mgm2PoolVec = PoolEntry(3); - PoolEntry mgm3PoolVec = PoolEntry(3); - PoolEntry imtqMgmPoolVec = PoolEntry(3); + acsctrl::MgmDataRaw mgmDataRaw; + PoolEntry mgm0VecRaw = PoolEntry(3); + PoolEntry mgm1VecRaw = PoolEntry(3); + PoolEntry mgm2VecRaw = PoolEntry(3); + PoolEntry mgm3VecRaw = PoolEntry(3); + PoolEntry imtqMgmVecRaw = PoolEntry(3); PoolEntry imtqCalActStatus = PoolEntry(); - void copyMgmData(); - // Sun Sensors - - acsctrl::SusDataRaw susData; - - std::array susSets{ - SUS::SusDataset(objects::SUS_0_N_LOC_XFYFZM_PT_XF), - SUS::SusDataset(objects::SUS_1_N_LOC_XBYFZM_PT_XB), - SUS::SusDataset(objects::SUS_2_N_LOC_XFYBZB_PT_YB), - SUS::SusDataset(objects::SUS_3_N_LOC_XFYBZF_PT_YF), - SUS::SusDataset(objects::SUS_4_N_LOC_XMYFZF_PT_ZF), - SUS::SusDataset(objects::SUS_5_N_LOC_XFYMZB_PT_ZB), - SUS::SusDataset(objects::SUS_6_R_LOC_XFYBZM_PT_XF), - SUS::SusDataset(objects::SUS_7_R_LOC_XBYBZM_PT_XB), - SUS::SusDataset(objects::SUS_8_R_LOC_XBYBZB_PT_YB), - SUS::SusDataset(objects::SUS_9_R_LOC_XBYBZB_PT_YF), - SUS::SusDataset(objects::SUS_10_N_LOC_XMYBZF_PT_ZF), - SUS::SusDataset(objects::SUS_11_R_LOC_XBYMZB_PT_ZB), - }; - - PoolEntry sus0PoolVec = PoolEntry(6); - PoolEntry sus1PoolVec = PoolEntry(6); - PoolEntry sus2PoolVec = PoolEntry(6); - PoolEntry sus3PoolVec = PoolEntry(6); - PoolEntry sus4PoolVec = PoolEntry(6); - PoolEntry sus5PoolVec = PoolEntry(6); - PoolEntry sus6PoolVec = PoolEntry(6); - PoolEntry sus7PoolVec = PoolEntry(6); - PoolEntry sus8PoolVec = PoolEntry(6); - PoolEntry sus9PoolVec = PoolEntry(6); - PoolEntry sus10PoolVec = PoolEntry(6); - PoolEntry sus11PoolVec = PoolEntry(6); + acsctrl::MgmDataProcessed mgmDataProcessed; + PoolEntry mgm0VecProc = PoolEntry(3); + PoolEntry mgm1VecProc = PoolEntry(3); + PoolEntry mgm2VecProc = PoolEntry(3); + PoolEntry mgm3VecProc = PoolEntry(3); + PoolEntry mgm4VecProc = PoolEntry(3); + PoolEntry mgmVecTot = PoolEntry(3); + PoolEntry mgmVecTotDer = PoolEntry(3); + PoolEntry magIgrf = PoolEntry(3); + // SUSs + acsctrl::SusDataRaw susDataRaw; + PoolEntry sus0ValRaw = PoolEntry(6); + PoolEntry sus1ValRaw = PoolEntry(6); + PoolEntry sus2ValRaw = PoolEntry(6); + PoolEntry sus3ValRaw = PoolEntry(6); + PoolEntry sus4ValRaw = PoolEntry(6); + PoolEntry sus5ValRaw = PoolEntry(6); + PoolEntry sus6ValRaw = PoolEntry(6); + PoolEntry sus7ValRaw = PoolEntry(6); + PoolEntry sus8ValRaw = PoolEntry(6); + PoolEntry sus9ValRaw = PoolEntry(6); + PoolEntry sus10ValRaw = PoolEntry(6); + PoolEntry sus11ValRaw = PoolEntry(6); void copySusData(); + acsctrl::SusDataProcessed susDataProcessed; + PoolEntry sus0VecProc = PoolEntry(3); + PoolEntry sus1VecProc = PoolEntry(3); + PoolEntry sus2VecProc = PoolEntry(3); + PoolEntry sus3VecProc = PoolEntry(3); + PoolEntry sus4VecProc = PoolEntry(3); + PoolEntry sus5VecProc = PoolEntry(3); + PoolEntry sus6VecProc = PoolEntry(3); + PoolEntry sus7VecProc = PoolEntry(3); + PoolEntry sus8VecProc = PoolEntry(3); + PoolEntry sus9VecProc = PoolEntry(3); + PoolEntry sus10VecProc = PoolEntry(3); + PoolEntry sus11VecProc = PoolEntry(3); + PoolEntry susVecTot = PoolEntry(3); + PoolEntry susVecTotDer = PoolEntry(3); + PoolEntry sunIjk = PoolEntry(3); + + // GYRs + acsctrl::GyrDataRaw gyrDataRaw; + PoolEntry gyr0VecRaw = PoolEntry(3); + PoolEntry gyr1VecRaw = PoolEntry(3); + PoolEntry gyr2VecRaw = PoolEntry(3); + PoolEntry gyr3VecRaw = PoolEntry(3); + void copyGyrData(); + + acsctrl::GyrDataProcessed gyrDataProcessed; + PoolEntry gyr0VecProc = PoolEntry(3); + PoolEntry gyr1VecProc = PoolEntry(3); + PoolEntry gyr2VecProc = PoolEntry(3); + PoolEntry gyr3VecProc = PoolEntry(3); + PoolEntry gyrVecTot = PoolEntry(3); + + // GPS + acsctrl::GpsDataProcessed gpsDataProcessed; + PoolEntry gcLatitude = PoolEntry(); + PoolEntry gdLongitude = PoolEntry(); + + // MEKF + acsctrl::MekfData mekfData; + PoolEntry quatMekf = PoolEntry(4); + PoolEntry satRotRateMekf = PoolEntry(3); + + // Actuator CMD + acsctrl::ActuatorCmdData actuatorCmdData; + PoolEntry rwTargetTorque = PoolEntry(4); + PoolEntry rwTargetSpeed = PoolEntry(4); + PoolEntry mtqTargetDipole = PoolEntry(3); + // Initial delay to make sure all pool variables have been initialized their owners Countdown initialCountdown = Countdown(INIT_DELAY); }; diff --git a/mission/controller/acs/OutputValues.cpp b/mission/controller/acs/OutputValues.cpp index d035f621..42730fb3 100644 --- a/mission/controller/acs/OutputValues.cpp +++ b/mission/controller/acs/OutputValues.cpp @@ -1,19 +1,9 @@ -/* - * OutputValues.cpp - * - * Created on: 30 Mar 2022 - * Author: rooob - */ #include "OutputValues.h" namespace ACS { -OutputValues::OutputValues(){ +OutputValues::OutputValues() {} -} +OutputValues::~OutputValues() {} -OutputValues::~OutputValues(){ - -} - -} +} // namespace ACS diff --git a/mission/controller/acs/OutputValues.h b/mission/controller/acs/OutputValues.h index c9fc71f1..bd182f42 100644 --- a/mission/controller/acs/OutputValues.h +++ b/mission/controller/acs/OutputValues.h @@ -1,51 +1,44 @@ -/* - * OutputValues.h - * - * Created on: 30 Mar 2022 - * Author: rooob - */ +#include + +#include "../controllerdefinitions/AcsCtrlDefinitions.h" #ifndef OUTPUTVALUES_H_ #define OUTPUTVALUES_H_ - namespace ACS { class OutputValues { + public: + OutputValues(); + virtual ~OutputValues(); -public: + double magFieldEst[3]; // sensor fusion (G) // output value + bool magFieldEstValid; + double magFieldModel[3]; // igrf (IJK) // + bool magFieldModelValid; + double magneticFieldVectorDerivative[3]; + bool magneticFieldVectorDerivativeValid; - OutputValues(); - virtual ~OutputValues(); + bool mgmUpdated; // ToDo: ???? - double magFieldEst[3]; // sensor fusion (G) - bool magFieldEstValid; - double magFieldModel[3]; //igrf (IJK) - bool magFieldModelValid; - double magneticFieldVectorDerivative[3]; - bool magneticFieldVectorDerivativeValid; + double sunDirEst[3]; // sensor fusion (G) + bool sunDirEstValid; + double sunDirModel[3]; // sun model (IJK) + bool sunDirModelValid; - bool mgmUpdated; + double quatMekfBJ[4]; // mekf + bool quatMekfBJValid; - double sunDirEst[3]; // sensor fusion (G) - bool sunDirEstValid; - double sunDirModel[3]; //sun model (IJK) - bool sunDirModelValid; + double satRateEst[3]; + bool satRateEstValid; + double satRateMekf[3]; // after mekf with correction of bias + bool satRateMekfValid; + double sunVectorDerivative[3]; + bool sunVectorDerivativeValid; - double quatMekfBJ[4]; //mekf - bool quatMekfBJValid; - - double satRateEst[3]; - bool satRateEstValid; - double satRateMekf[3]; // after mekf with correction of bias - bool satRateMekfValid; - double sunVectorDerivative[3]; - bool sunVectorDerivativeValid; - - double gcLatitude; // geocentric latitude, radian - double gdLongitude; // Radian longitude + double gcLatitude; // geocentric latitude, radian + double gdLongitude; // Radian longitude }; -} - +} // namespace ACS #endif /*OUTPUTVALUES_H_*/ diff --git a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h index 4a608f71..bb0a40ae 100644 --- a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h +++ b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h @@ -15,7 +15,7 @@ enum SetIds : uint32_t { SUS_PROCESSED_DATA, GYR_SENSOR_DATA, GYR_PROCESSED_DATA, - GPS_SENSOR_DATA, + GPS_PROCESSED_DATA, MEKF_DATA, ACTUATOR_CMD_DATA }; @@ -214,8 +214,7 @@ class GyrDataProcessed : public StaticLocalDataSet { class GpsDataProcessed : public StaticLocalDataSet { public: - GpsDataProcessed(HasLocalDataPoolIF* hkOwner) - : StaticLocalDataSet(hkOwner, GPS_SET_PROCESSED_ENTRIES) {} + GpsDataProcessed(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, GPS_PROCESSED_DATA) {} lp_var_t gcLatitude = lp_var_t(sid.objectId, GC_LATITUDE, this); lp_var_t gdLongitude = lp_var_t(sid.objectId, GD_LONGITUDE, this); -- 2.34.1 From 69099881bd112c4938726d21227bc9743c56273b Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 25 Oct 2022 11:31:54 +0200 Subject: [PATCH 075/101] small stuff --- mission/controller/AcsController.cpp | 33 +++++++++++---------------- mission/controller/AcsController.h | 2 +- mission/controller/acs/OutputValues.h | 2 +- 3 files changed, 15 insertions(+), 22 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index b42d9c83..e82cbb7d 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -97,7 +97,7 @@ void AcsController::performSafe() { sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); ReturnValue_t validMekf; - navigation.useMekf(&sensorValues, &outputValues, &validMekf); // DOES THIS WORK WITH VALID? + navigation.useMekf(&sensorValues, &outputValues, &validMekf); // Give desired satellite rate and sun direction to align double satRateSafe[3] = {0, 0, 0}, sunTargetDir[3] = {0, 0, 0}; @@ -127,25 +127,18 @@ void AcsController::performSafe() { if (outputValues.satRateMekfValid && VectorOperations::norm(outputValues.satRateMekf, 3) > acsParameters.detumbleParameter.omegaDetumbleStart) { detumbleCounter++; - } - - else if (outputValues.satRateEstValid && - VectorOperations::norm(outputValues.satRateEst, 3) > - acsParameters.detumbleParameter.omegaDetumbleStart) { + } else if (outputValues.satRateEstValid && + VectorOperations::norm(outputValues.satRateEst, 3) > + acsParameters.detumbleParameter.omegaDetumbleStart) { detumbleCounter++; - - } - - else { + } else { detumbleCounter = 0; } - if (detumbleCounter > acsParameters.detumbleParameter.detumblecounter) { submode = SUBMODE_DETUMBLE; detumbleCounter = 0; } - - // commanding.magnetorquesDipol(); + // commanding.magnetorquesDipol(); } void AcsController::performDetumble() { @@ -154,7 +147,6 @@ void AcsController::performDetumble() { timeval now; Clock::getClock_timeval(&now); - // Clock::getUptime(&now); sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); ReturnValue_t validMekf; @@ -170,14 +162,13 @@ void AcsController::performDetumble() { if (outputValues.satRateMekfValid && VectorOperations::norm(outputValues.satRateMekf, 3) < acsParameters.detumbleParameter.omegaDetumbleEnd) { detumbleCounter++; - } - - else if (outputValues.satRateEstValid && - VectorOperations::norm(outputValues.satRateEst, 3) < - acsParameters.detumbleParameter.omegaDetumbleEnd) { + } else if (outputValues.satRateEstValid && + VectorOperations::norm(outputValues.satRateEst, 3) < + acsParameters.detumbleParameter.omegaDetumbleEnd) { detumbleCounter++; + } else { + detumbleCounter = 0; } - if (detumbleCounter > acsParameters.detumbleParameter.detumblecounter) { submode = SUBMODE_SAFE; detumbleCounter = 0; @@ -235,6 +226,7 @@ ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localD localDataPoolMap.emplace(acsctrl::PoolIds::MGM_1_VEC, &mgm1VecProc); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_2_VEC, &mgm2VecProc); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_3_VEC, &mgm3VecProc); + localDataPoolMap.emplace(acsctrl::PoolIds::MGM_4_VEC, &mgm4VecProc); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_VEC_TOT, &mgmVecTot); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_VEC_TOT_DERIVATIVE, &mgmVecTotDer); localDataPoolMap.emplace(acsctrl::PoolIds::MAG_IGRF_MODEL, &magIgrf); @@ -539,3 +531,4 @@ void AcsController::copyGyrData() { } } } + diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index 87aaf37c..dcd78621 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -82,7 +82,7 @@ class AcsController : public ExtendedControllerBase { PoolEntry mgm2VecProc = PoolEntry(3); PoolEntry mgm3VecProc = PoolEntry(3); PoolEntry mgm4VecProc = PoolEntry(3); - PoolEntry mgmVecTot = PoolEntry(3); + PoolEntry mgmVecTot = PoolEntry(3); PoolEntry mgmVecTotDer = PoolEntry(3); PoolEntry magIgrf = PoolEntry(3); diff --git a/mission/controller/acs/OutputValues.h b/mission/controller/acs/OutputValues.h index bd182f42..bb1ed007 100644 --- a/mission/controller/acs/OutputValues.h +++ b/mission/controller/acs/OutputValues.h @@ -19,7 +19,7 @@ class OutputValues { double magneticFieldVectorDerivative[3]; bool magneticFieldVectorDerivativeValid; - bool mgmUpdated; // ToDo: ???? + bool mgmUpdated; // ToDo: relic from FLP. most likely not used double sunDirEst[3]; // sensor fusion (G) bool sunDirEstValid; -- 2.34.1 From 44dda9455d9105e203dd896ff96e93097c8a26cb Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 26 Oct 2022 17:13:23 +0200 Subject: [PATCH 076/101] SensorProcessing writes to AcsController DataSets now --- mission/controller/AcsController.cpp | 9 +- mission/controller/acs/SensorProcessing.cpp | 595 ++++++++++++-------- mission/controller/acs/SensorProcessing.h | 31 +- 3 files changed, 380 insertions(+), 255 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index e82cbb7d..0cb4f330 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -95,7 +95,8 @@ void AcsController::performSafe() { timeval now; Clock::getClock_timeval(&now); - sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); + sensorProcessing.process(now, &sensorValues, &mgmDataProcessed, &susDataProcessed, + &gyrDataProcessed, &gpsDataProcessed, &acsParameters); ReturnValue_t validMekf; navigation.useMekf(&sensorValues, &outputValues, &validMekf); @@ -148,7 +149,8 @@ void AcsController::performDetumble() { timeval now; Clock::getClock_timeval(&now); - sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); + sensorProcessing.process(now, &sensorValues, &mgmDataProcessed, &susDataProcessed, + &gyrDataProcessed, &gpsDataProcessed, &acsParameters); ReturnValue_t validMekf; navigation.useMekf(&sensorValues, &outputValues, &validMekf); @@ -182,7 +184,8 @@ void AcsController::performPointingCtrl() { timeval now; Clock::getClock_timeval(&now); - sensorProcessing.process(now, &sensorValues, &outputValues, &acsParameters); + sensorProcessing.process(now, &sensorValues, &mgmDataProcessed, &susDataProcessed, + &gyrDataProcessed, &gpsDataProcessed, &acsParameters); ReturnValue_t validMekf; navigation.useMekf(&sensorValues, &outputValues, &validMekf); diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index 8c89dda4..1baa4007 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -1,5 +1,6 @@ #include "SensorProcessing.h" +#include #include #include #include @@ -13,27 +14,35 @@ using namespace Math; -SensorProcessing::SensorProcessing(AcsParameters *acsParameters_) : savedMagFieldEst{0, 0, 0} { - validMagField = false; - validGcLatitude = false; -} +SensorProcessing::SensorProcessing(AcsParameters *acsParameters_) + : savedMgmVecTot{0, 0, 0}, validMagField(false), validGcLatitude(false) {} SensorProcessing::~SensorProcessing() {} -bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const float *mgm1Value, +void SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const float *mgm1Value, bool mgm1valid, const float *mgm2Value, bool mgm2valid, const float *mgm3Value, bool mgm3valid, const float *mgm4Value, bool mgm4valid, timeval timeOfMgmMeasurement, const AcsParameters::MgmHandlingParameters *mgmParameters, - const double gpsLatitude, const double gpsLongitude, - const double gpsAltitude, bool gpsValid, double *magFieldEst, - bool *outputValid, double *magFieldModel, - bool *magFieldModelValid, double *magneticFieldVectorDerivative, - bool *magneticFieldVectorDerivativeValid) { + acsctrl::GpsDataProcessed *gpsDataProcessed, + const double gpsAltitude, bool gpsValid, + acsctrl::MgmDataProcessed *mgmDataProcessed) { if (!mgm0valid && !mgm1valid && !mgm2valid && !mgm3valid && !mgm4valid) { - *outputValid = false; - validMagField = false; - return false; + { + PoolReadGuard pg(mgmDataProcessed); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(mgmDataProcessed->mgm0vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(mgmDataProcessed->mgm1vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(mgmDataProcessed->mgm2vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(mgmDataProcessed->mgm3vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(mgmDataProcessed->mgm4vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(mgmDataProcessed->mgmVecTot.value, zeroVector, 3 * sizeof(float)); + std::memcpy(mgmDataProcessed->mgmVecTotDerivative.value, zeroVector, 3 * sizeof(float)); + std::memcpy(mgmDataProcessed->magIgrfModel.value, zeroVector, 3 * sizeof(double)); + mgmDataProcessed->setValidity(false, true); + } + } + return; } float mgm0ValueNoBias[3] = {0, 0, 0}, mgm1ValueNoBias[3] = {0, 0, 0}, mgm2ValueNoBias[3] = {0, 0, 0}, mgm3ValueNoBias[3] = {0, 0, 0}, @@ -104,34 +113,26 @@ bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const sensorFusionDenominator[i] += 1 / mgmParameters->mgm4variance[i]; } } + float mgmVecTot[3] = {0.0, 0.0, 0.0}; for (uint8_t i = 0; i < 3; i++) { - magFieldEst[i] = sensorFusionNumerator[i] / sensorFusionDenominator[i]; + mgmVecTot[i] = sensorFusionNumerator[i] / sensorFusionDenominator[i]; } - validMagField = true; - //-----------------------Mag Rate Computation --------------------------------------------------- + //-----------------------Mgm Rate Computation --------------------------------------------------- + float mgmVecTotDerivative[3] = {0.0, 0.0, 0.0}; + bool mgmVecTotDerivativeValid = false; double timeDiff = timevalOperations::toDouble(timeOfMgmMeasurement - timeOfSavedMagFieldEst); - for (uint8_t i = 0; i < 3; i++) { - magneticFieldVectorDerivative[i] = (magFieldEst[i] - savedMagFieldEst[i]) / timeDiff; - savedMagFieldEst[i] = magFieldEst[i]; + if (timeOfSavedMagFieldEst.tv_sec != 0) { + for (uint8_t i = 0; i < 3; i++) { + mgmVecTotDerivative[i] = (mgmVecTot[i] - savedMgmVecTot[i]) / timeDiff; + savedMgmVecTot[i] = mgmVecTot[i]; + } } - - *magneticFieldVectorDerivativeValid = true; - if (timeOfSavedMagFieldEst.tv_sec == 0) { - magneticFieldVectorDerivative[0] = 0; - magneticFieldVectorDerivative[1] = 0; - magneticFieldVectorDerivative[2] = 0; - *magneticFieldVectorDerivativeValid = false; - } - timeOfSavedMagFieldEst = timeOfMgmMeasurement; - *outputValid = true; - // ---------------- IGRF- 13 Implementation here ------------------------------------------------ - if (!gpsValid) { - *magFieldModelValid = false; - } else { + double magIgrfModel[3] = {0.0, 0.0, 0.0}; + if (gpsValid) { // Should be existing class object which will be called and modified here. Igrf13Model igrf13; // So the line above should not be done here. Update: Can be done here as long updated coffs @@ -139,12 +140,32 @@ bool SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const igrf13.updateCoeffGH(timeOfMgmMeasurement); // maybe put a condition here, to only update after a full day, this // class function has around 700 steps to perform - igrf13.magFieldComp(gpsLongitude, gpsLatitude, gpsAltitude, timeOfMgmMeasurement, - magFieldModel); - *magFieldModelValid = false; + igrf13.magFieldComp(gpsDataProcessed->gdLongitude.value, gpsDataProcessed->gcLatitude.value, + gpsAltitude, timeOfMgmMeasurement, magIgrfModel); + } + { + PoolReadGuard pg(mgmDataProcessed); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(mgmDataProcessed->mgm0vec.value, mgm0ValueBody, 3 * sizeof(float)); + mgmDataProcessed->mgm0vec.setValid(mgm0valid); + std::memcpy(mgmDataProcessed->mgm1vec.value, mgm1ValueBody, 3 * sizeof(float)); + mgmDataProcessed->mgm1vec.setValid(mgm1valid); + std::memcpy(mgmDataProcessed->mgm2vec.value, mgm2ValueBody, 3 * sizeof(float)); + mgmDataProcessed->mgm2vec.setValid(mgm2valid); + std::memcpy(mgmDataProcessed->mgm3vec.value, mgm3ValueBody, 3 * sizeof(float)); + mgmDataProcessed->mgm3vec.setValid(mgm3valid); + std::memcpy(mgmDataProcessed->mgm4vec.value, mgm4ValueBody, 3 * sizeof(float)); + mgmDataProcessed->mgm4vec.setValid(mgm4valid); + std::memcpy(mgmDataProcessed->mgmVecTot.value, mgmVecTot, 3 * sizeof(float)); + mgmDataProcessed->mgmVecTot.setValid(true); + std::memcpy(mgmDataProcessed->mgmVecTotDerivative.value, mgmVecTotDerivative, + 3 * sizeof(float)); + mgmDataProcessed->mgmVecTotDerivative.setValid(mgmVecTotDerivativeValid); + std::memcpy(mgmDataProcessed->magIgrfModel.value, magIgrfModel, 3 * sizeof(double)); + mgmDataProcessed->magIgrfModel.setValid(gpsValid); + mgmDataProcessed->setValidity(true, false); + } } - - return true; } void SensorProcessing::processSus( @@ -155,9 +176,8 @@ void SensorProcessing::processSus( const uint16_t *sus8Value, bool sus8valid, const uint16_t *sus9Value, bool sus9valid, const uint16_t *sus10Value, bool sus10valid, const uint16_t *sus11Value, bool sus11valid, timeval timeOfSusMeasurement, const AcsParameters::SusHandlingParameters *susParameters, - const AcsParameters::SunModelParameters *sunModelParameters, double *sunDirEst, - bool *sunDirEstValid, double *sunVectorInertial, bool *sunVectorInertialValid, - double *sunVectorDerivative, bool *sunVectorDerivativeValid) { + const AcsParameters::SunModelParameters *sunModelParameters, + acsctrl::SusDataProcessed *susDataProcessed) { if (sus0valid) { sus0valid = susConverter.checkSunSensorData(sus0Value); } @@ -197,142 +217,176 @@ void SensorProcessing::processSus( if (!sus0valid && !sus1valid && !sus2valid && !sus3valid && !sus4valid && !sus5valid && !sus6valid && !sus7valid && !sus8valid && !sus9valid && !sus10valid && !sus11valid) { - *sunDirEstValid = false; - return; - } else { - // WARNING: NOT TRANSFORMED IN BODY FRAME YET - // Transformation into Geomtry Frame - float sus0VecBody[3] = {0, 0, 0}, sus1VecBody[3] = {0, 0, 0}, sus2VecBody[3] = {0, 0, 0}, - sus3VecBody[3] = {0, 0, 0}, sus4VecBody[3] = {0, 0, 0}, sus5VecBody[3] = {0, 0, 0}, - sus6VecBody[3] = {0, 0, 0}, sus7VecBody[3] = {0, 0, 0}, sus8VecBody[3] = {0, 0, 0}, - sus9VecBody[3] = {0, 0, 0}, sus10VecBody[3] = {0, 0, 0}, sus11VecBody[3] = {0, 0, 0}; - - if (sus0valid) { - MatrixOperations::multiply( - susParameters->sus0orientationMatrix[0], - susConverter.getSunVectorSensorFrame(sus0Value, susParameters->sus0coeffAlpha, - susParameters->sus0coeffBeta), - sus0VecBody, 3, 3, 1); - } - if (sus1valid) { - MatrixOperations::multiply( - susParameters->sus1orientationMatrix[0], - susConverter.getSunVectorSensorFrame(sus1Value, susParameters->sus1coeffAlpha, - susParameters->sus1coeffBeta), - sus1VecBody, 3, 3, 1); - } - if (sus2valid) { - MatrixOperations::multiply( - susParameters->sus2orientationMatrix[0], - susConverter.getSunVectorSensorFrame(sus2Value, susParameters->sus2coeffAlpha, - susParameters->sus2coeffBeta), - sus2VecBody, 3, 3, 1); - } - if (sus3valid) { - MatrixOperations::multiply( - susParameters->sus3orientationMatrix[0], - susConverter.getSunVectorSensorFrame(sus3Value, susParameters->sus3coeffAlpha, - susParameters->sus3coeffBeta), - sus3VecBody, 3, 3, 1); - } - if (sus4valid) { - MatrixOperations::multiply( - susParameters->sus4orientationMatrix[0], - susConverter.getSunVectorSensorFrame(sus4Value, susParameters->sus4coeffAlpha, - susParameters->sus4coeffBeta), - sus4VecBody, 3, 3, 1); - } - if (sus5valid) { - MatrixOperations::multiply( - susParameters->sus5orientationMatrix[0], - susConverter.getSunVectorSensorFrame(sus5Value, susParameters->sus5coeffAlpha, - susParameters->sus5coeffBeta), - sus5VecBody, 3, 3, 1); - } - if (sus6valid) { - MatrixOperations::multiply( - susParameters->sus6orientationMatrix[0], - susConverter.getSunVectorSensorFrame(sus6Value, susParameters->sus6coeffAlpha, - susParameters->sus6coeffBeta), - sus6VecBody, 3, 3, 1); - } - if (sus7valid) { - MatrixOperations::multiply( - susParameters->sus7orientationMatrix[0], - susConverter.getSunVectorSensorFrame(sus7Value, susParameters->sus7coeffAlpha, - susParameters->sus7coeffBeta), - sus7VecBody, 3, 3, 1); - } - if (sus8valid) { - MatrixOperations::multiply( - susParameters->sus8orientationMatrix[0], - susConverter.getSunVectorSensorFrame(sus8Value, susParameters->sus8coeffAlpha, - susParameters->sus8coeffBeta), - sus8VecBody, 3, 3, 1); - } - if (sus9valid) { - MatrixOperations::multiply( - susParameters->sus9orientationMatrix[0], - susConverter.getSunVectorSensorFrame(sus9Value, susParameters->sus9coeffAlpha, - susParameters->sus9coeffBeta), - sus9VecBody, 3, 3, 1); - } - if (sus10valid) { - MatrixOperations::multiply( - susParameters->sus10orientationMatrix[0], - susConverter.getSunVectorSensorFrame(sus10Value, susParameters->sus10coeffAlpha, - susParameters->sus10coeffBeta), - sus10VecBody, 3, 3, 1); - } - if (sus11valid) { - MatrixOperations::multiply( - susParameters->sus11orientationMatrix[0], - susConverter.getSunVectorSensorFrame(sus11Value, susParameters->sus11coeffAlpha, - susParameters->sus11coeffBeta), - sus11VecBody, 3, 3, 1); - } - - /* ------ Mean Value: susDirEst ------ */ - bool validIds[12] = {sus0valid, sus1valid, sus2valid, sus3valid, sus4valid, sus5valid, - sus6valid, sus7valid, sus8valid, sus9valid, sus10valid, sus11valid}; - float susVecBody[3][12] = {{sus0VecBody[0], sus1VecBody[0], sus2VecBody[0], sus3VecBody[0], - sus4VecBody[0], sus5VecBody[0], sus6VecBody[0], sus7VecBody[0], - sus8VecBody[0], sus9VecBody[0], sus10VecBody[0], sus11VecBody[0]}, - {sus0VecBody[1], sus1VecBody[1], sus2VecBody[1], sus3VecBody[1], - sus4VecBody[1], sus5VecBody[1], sus6VecBody[1], sus7VecBody[1], - sus8VecBody[1], sus9VecBody[1], sus10VecBody[1], sus11VecBody[1]}, - {sus0VecBody[2], sus1VecBody[2], sus2VecBody[2], sus3VecBody[2], - sus4VecBody[2], sus5VecBody[2], sus6VecBody[2], sus7VecBody[2], - sus8VecBody[2], sus9VecBody[2], sus10VecBody[2], sus11VecBody[2]}}; - - double susMeanValue[3] = {0, 0, 0}; - for (uint8_t i = 0; i < 12; i++) { - if (validIds[i]) { - susMeanValue[0] += susVecBody[0][i]; - susMeanValue[1] += susVecBody[1][i]; - susMeanValue[2] += susVecBody[2][i]; + { + PoolReadGuard pg(susDataProcessed); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susDataProcessed->sus0vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->sus1vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->sus2vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->sus3vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->sus4vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->sus5vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->sus6vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->sus7vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->sus8vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->sus9vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->sus10vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->sus11vec.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->susVecTot.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->susVecTotDerivative.value, zeroVector, 3 * sizeof(float)); + std::memcpy(susDataProcessed->sunIjkModel.value, zeroVector, 3 * sizeof(double)); + susDataProcessed->setValidity(false, true); } } - VectorOperations::normalize(susMeanValue, sunDirEst, 3); - *sunDirEstValid = true; + return; } + // WARNING: NOT TRANSFORMED IN BODY FRAME YET + // Transformation into Geomtry Frame + float sus0VecBody[3] = {0, 0, 0}, sus1VecBody[3] = {0, 0, 0}, sus2VecBody[3] = {0, 0, 0}, + sus3VecBody[3] = {0, 0, 0}, sus4VecBody[3] = {0, 0, 0}, sus5VecBody[3] = {0, 0, 0}, + sus6VecBody[3] = {0, 0, 0}, sus7VecBody[3] = {0, 0, 0}, sus8VecBody[3] = {0, 0, 0}, + sus9VecBody[3] = {0, 0, 0}, sus10VecBody[3] = {0, 0, 0}, sus11VecBody[3] = {0, 0, 0}; + + if (sus0valid) { + MatrixOperations::multiply( + susParameters->sus0orientationMatrix[0], + susConverter.getSunVectorSensorFrame(sus0Value, susParameters->sus0coeffAlpha, + susParameters->sus0coeffBeta), + sus0VecBody, 3, 3, 1); + } + { + PoolReadGuard pg(susDataProcessed); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susDataProcessed->sus0vec.value, sus0VecBody, 3 * sizeof(float)); + susDataProcessed->sus0vec.setValid(sus0valid); + if (!sus0valid) { + std::memcpy(susDataProcessed->sus0vec.value, zeroVector, 3 * sizeof(float)); + } + } + } + if (sus1valid) { + MatrixOperations::multiply( + susParameters->sus1orientationMatrix[0], + susConverter.getSunVectorSensorFrame(sus1Value, susParameters->sus1coeffAlpha, + susParameters->sus1coeffBeta), + sus1VecBody, 3, 3, 1); + } + { + PoolReadGuard pg(susDataProcessed); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susDataProcessed->sus1vec.value, sus1VecBody, 3 * sizeof(float)); + susDataProcessed->sus1vec.setValid(sus1valid); + if (!sus1valid) { + std::memcpy(susDataProcessed->sus1vec.value, zeroVector, 3 * sizeof(float)); + } + } + } + if (sus2valid) { + MatrixOperations::multiply( + susParameters->sus2orientationMatrix[0], + susConverter.getSunVectorSensorFrame(sus2Value, susParameters->sus2coeffAlpha, + susParameters->sus2coeffBeta), + sus2VecBody, 3, 3, 1); + } + if (sus3valid) { + MatrixOperations::multiply( + susParameters->sus3orientationMatrix[0], + susConverter.getSunVectorSensorFrame(sus3Value, susParameters->sus3coeffAlpha, + susParameters->sus3coeffBeta), + sus3VecBody, 3, 3, 1); + } + if (sus4valid) { + MatrixOperations::multiply( + susParameters->sus4orientationMatrix[0], + susConverter.getSunVectorSensorFrame(sus4Value, susParameters->sus4coeffAlpha, + susParameters->sus4coeffBeta), + sus4VecBody, 3, 3, 1); + } + if (sus5valid) { + MatrixOperations::multiply( + susParameters->sus5orientationMatrix[0], + susConverter.getSunVectorSensorFrame(sus5Value, susParameters->sus5coeffAlpha, + susParameters->sus5coeffBeta), + sus5VecBody, 3, 3, 1); + } + if (sus6valid) { + MatrixOperations::multiply( + susParameters->sus6orientationMatrix[0], + susConverter.getSunVectorSensorFrame(sus6Value, susParameters->sus6coeffAlpha, + susParameters->sus6coeffBeta), + sus6VecBody, 3, 3, 1); + } + if (sus7valid) { + MatrixOperations::multiply( + susParameters->sus7orientationMatrix[0], + susConverter.getSunVectorSensorFrame(sus7Value, susParameters->sus7coeffAlpha, + susParameters->sus7coeffBeta), + sus7VecBody, 3, 3, 1); + } + if (sus8valid) { + MatrixOperations::multiply( + susParameters->sus8orientationMatrix[0], + susConverter.getSunVectorSensorFrame(sus8Value, susParameters->sus8coeffAlpha, + susParameters->sus8coeffBeta), + sus8VecBody, 3, 3, 1); + } + if (sus9valid) { + MatrixOperations::multiply( + susParameters->sus9orientationMatrix[0], + susConverter.getSunVectorSensorFrame(sus9Value, susParameters->sus9coeffAlpha, + susParameters->sus9coeffBeta), + sus9VecBody, 3, 3, 1); + } + if (sus10valid) { + MatrixOperations::multiply( + susParameters->sus10orientationMatrix[0], + susConverter.getSunVectorSensorFrame(sus10Value, susParameters->sus10coeffAlpha, + susParameters->sus10coeffBeta), + sus10VecBody, 3, 3, 1); + } + if (sus11valid) { + MatrixOperations::multiply( + susParameters->sus11orientationMatrix[0], + susConverter.getSunVectorSensorFrame(sus11Value, susParameters->sus11coeffAlpha, + susParameters->sus11coeffBeta), + sus11VecBody, 3, 3, 1); + } + + /* ------ Mean Value: susDirEst ------ */ + bool validIds[12] = {sus0valid, sus1valid, sus2valid, sus3valid, sus4valid, sus5valid, + sus6valid, sus7valid, sus8valid, sus9valid, sus10valid, sus11valid}; + float susVecBody[3][12] = {{sus0VecBody[0], sus1VecBody[0], sus2VecBody[0], sus3VecBody[0], + sus4VecBody[0], sus5VecBody[0], sus6VecBody[0], sus7VecBody[0], + sus8VecBody[0], sus9VecBody[0], sus10VecBody[0], sus11VecBody[0]}, + {sus0VecBody[1], sus1VecBody[1], sus2VecBody[1], sus3VecBody[1], + sus4VecBody[1], sus5VecBody[1], sus6VecBody[1], sus7VecBody[1], + sus8VecBody[1], sus9VecBody[1], sus10VecBody[1], sus11VecBody[1]}, + {sus0VecBody[2], sus1VecBody[2], sus2VecBody[2], sus3VecBody[2], + sus4VecBody[2], sus5VecBody[2], sus6VecBody[2], sus7VecBody[2], + sus8VecBody[2], sus9VecBody[2], sus10VecBody[2], sus11VecBody[2]}}; + + float susMeanValue[3] = {0, 0, 0}; + for (uint8_t i = 0; i < 12; i++) { + if (validIds[i]) { + susMeanValue[0] += susVecBody[0][i]; + susMeanValue[1] += susVecBody[1][i]; + susMeanValue[2] += susVecBody[2][i]; + } + } + float susVecTot[3] = {0.0, 0.0, 0.0}; + VectorOperations::normalize(susMeanValue, susVecTot, 3); /* -------- Sun Derivatiative --------------------- */ + float susVecTotDerivative[3] = {0.0, 0.0, 0.0}; + bool susVecTotDerivativeValid = false; double timeDiff = timevalOperations::toDouble(timeOfSusMeasurement - timeOfSavedSusDirEst); - for (uint8_t i = 0; i < 3; i++) { - sunVectorDerivative[i] = (sunDirEst[i] - savedSunVector[i]) / timeDiff; - savedSunVector[i] = sunDirEst[i]; + if (timeOfSavedSusDirEst.tv_sec != 0) { + for (uint8_t i = 0; i < 3; i++) { + susVecTotDerivative[i] = (susVecTot[i] - savedSusVecTot[i]) / timeDiff; + savedSusVecTot[i] = susVecTot[i]; + } } - - *sunVectorDerivativeValid = true; - if (timeOfSavedSusDirEst.tv_sec == 0) { - sunVectorDerivative[0] = 0; - sunVectorDerivative[1] = 0; - sunVectorDerivative[2] = 0; - *sunVectorDerivativeValid = false; - } - timeOfSavedSusDirEst = timeOfSusMeasurement; /* -------- Sun Model Direction (IJK frame) ------- */ @@ -340,6 +394,7 @@ void SensorProcessing::processSus( double JD2000 = MathOperations::convertUnixToJD2000(timeOfSusMeasurement); // Julean Centuries + double sunIjkModel[3] = {0.0, 0.0, 0.0}; double JC2000 = JD2000 / 36525; double meanLongitude = @@ -351,11 +406,46 @@ void SensorProcessing::processSus( double epsilon = sunModelParameters->e - (sunModelParameters->e1) * JC2000; - sunVectorInertial[0] = cos(eclipticLongitude); - sunVectorInertial[1] = sin(eclipticLongitude) * cos(epsilon); - sunVectorInertial[2] = sin(eclipticLongitude) * sin(epsilon); - - *sunVectorInertialValid = true; + sunIjkModel[0] = cos(eclipticLongitude); + sunIjkModel[1] = sin(eclipticLongitude) * cos(epsilon); + sunIjkModel[2] = sin(eclipticLongitude) * sin(epsilon); + { + PoolReadGuard pg(susDataProcessed); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(susDataProcessed->sus0vec.value, sus0VecBody, 3 * sizeof(float)); + susDataProcessed->sus0vec.setValid(sus0valid); + std::memcpy(susDataProcessed->sus1vec.value, sus1VecBody, 3 * sizeof(float)); + susDataProcessed->sus1vec.setValid(sus1valid); + std::memcpy(susDataProcessed->sus2vec.value, sus2VecBody, 3 * sizeof(float)); + susDataProcessed->sus2vec.setValid(sus2valid); + std::memcpy(susDataProcessed->sus3vec.value, sus3VecBody, 3 * sizeof(float)); + susDataProcessed->sus3vec.setValid(sus3valid); + std::memcpy(susDataProcessed->sus4vec.value, sus4VecBody, 3 * sizeof(float)); + susDataProcessed->sus4vec.setValid(sus4valid); + std::memcpy(susDataProcessed->sus5vec.value, sus5VecBody, 3 * sizeof(float)); + susDataProcessed->sus5vec.setValid(sus5valid); + std::memcpy(susDataProcessed->sus6vec.value, sus6VecBody, 3 * sizeof(float)); + susDataProcessed->sus6vec.setValid(sus6valid); + std::memcpy(susDataProcessed->sus7vec.value, sus7VecBody, 3 * sizeof(float)); + susDataProcessed->sus7vec.setValid(sus7valid); + std::memcpy(susDataProcessed->sus8vec.value, sus8VecBody, 3 * sizeof(float)); + susDataProcessed->sus8vec.setValid(sus8valid); + std::memcpy(susDataProcessed->sus9vec.value, sus9VecBody, 3 * sizeof(float)); + susDataProcessed->sus9vec.setValid(sus9valid); + std::memcpy(susDataProcessed->sus10vec.value, sus10VecBody, 3 * sizeof(float)); + susDataProcessed->sus10vec.setValid(sus10valid); + std::memcpy(susDataProcessed->sus11vec.value, sus11VecBody, 3 * sizeof(float)); + susDataProcessed->sus11vec.setValid(sus11valid); + std::memcpy(susDataProcessed->susVecTot.value, susVecTot, 3 * sizeof(float)); + susDataProcessed->susVecTot.setValid(true); + std::memcpy(susDataProcessed->susVecTotDerivative.value, susVecTotDerivative, + 3 * sizeof(float)); + susDataProcessed->susVecTotDerivative.setValid(susVecTotDerivativeValid); + std::memcpy(susDataProcessed->sunIjkModel.value, sunIjkModel, 3 * sizeof(double)); + susDataProcessed->sunIjkModel.setValid(true); + susDataProcessed->setValidity(true, false); + } + } } void SensorProcessing::processGyr( @@ -366,133 +456,166 @@ void SensorProcessing::processGyr( const double gyr2axZvalue, bool gyr2axZvalid, const double gyr3axXvalue, bool gyr3axXvalid, const double gyr3axYvalue, bool gyr3axYvalid, const double gyr3axZvalue, bool gyr3axZvalid, timeval timeOfGyrMeasurement, const AcsParameters::GyrHandlingParameters *gyrParameters, - double *satRatEst, bool *satRateEstValid) { - if (!gyr0axXvalid && !gyr0axYvalid && !gyr0axZvalid && !gyr1axXvalid && !gyr1axYvalid && - !gyr1axZvalid && !gyr2axXvalid && !gyr2axYvalid && !gyr2axZvalid && !gyr3axXvalid && - !gyr3axYvalid && !gyr3axZvalid) { - *satRateEstValid = false; + acsctrl::GyrDataProcessed *gyrDataProcessed) { + bool gyr0valid = (gyr0axXvalid && gyr0axYvalid && gyr0axZvalid); + bool gyr1valid = (gyr1axXvalid && gyr1axYvalid && gyr1axZvalid); + bool gyr2valid = (gyr2axXvalid && gyr2axYvalid && gyr2axZvalid); + bool gyr3valid = (gyr3axXvalid && gyr3axYvalid && gyr3axZvalid); + if (!gyr0valid && !gyr1valid && !gyr2valid && !gyr3valid) { + { + PoolReadGuard pg(gyrDataProcessed); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(gyrDataProcessed->gyr0vec.value, zeroVector, 3 * sizeof(double)); + std::memcpy(gyrDataProcessed->gyr1vec.value, zeroVector, 3 * sizeof(double)); + std::memcpy(gyrDataProcessed->gyr2vec.value, zeroVector, 3 * sizeof(double)); + std::memcpy(gyrDataProcessed->gyr3vec.value, zeroVector, 3 * sizeof(double)); + std::memcpy(gyrDataProcessed->gyrVecTot.value, zeroVector, 3 * sizeof(double)); + gyrDataProcessed->setValidity(false, true); + } + } return; } // Transforming Values to the Body Frame (actually it is the geometry frame atm) double gyr0ValueBody[3] = {0, 0, 0}, gyr1ValueBody[3] = {0, 0, 0}, gyr2ValueBody[3] = {0, 0, 0}, gyr3ValueBody[3] = {0, 0, 0}; - bool validUnit[4] = {false, false, false, false}; - if (gyr0axXvalid && gyr0axYvalid && gyr0axZvalid) { + if (gyr0valid) { const double gyr0Value[3] = {gyr0axXvalue, gyr0axYvalue, gyr0axZvalue}; MatrixOperations::multiply(gyrParameters->gyr0orientationMatrix[0], gyr0Value, gyr0ValueBody, 3, 3, 1); - validUnit[0] = true; } - if (gyr1axXvalid && gyr1axYvalid && gyr1axZvalid) { + if (gyr1valid) { const double gyr1Value[3] = {gyr1axXvalue, gyr1axYvalue, gyr1axZvalue}; MatrixOperations::multiply(gyrParameters->gyr1orientationMatrix[0], gyr1Value, gyr1ValueBody, 3, 3, 1); - validUnit[1] = true; } - if (gyr2axXvalid && gyr2axYvalid && gyr2axZvalid) { + if (gyr2valid) { const double gyr2Value[3] = {gyr2axXvalue, gyr2axYvalue, gyr2axZvalue}; MatrixOperations::multiply(gyrParameters->gyr2orientationMatrix[0], gyr2Value, gyr2ValueBody, 3, 3, 1); - validUnit[2] = true; } - if (gyr3axXvalid && gyr3axYvalid && gyr3axZvalid) { + if (gyr3valid) { const double gyr3Value[3] = {gyr3axXvalue, gyr3axYvalue, gyr3axZvalue}; MatrixOperations::multiply(gyrParameters->gyr3orientationMatrix[0], gyr3Value, gyr3ValueBody, 3, 3, 1); - validUnit[3] = true; } /* -------- SatRateEst: Middle Value ------- */ // take ADIS measurements, if both avail // if just one ADIS measurement avail, perform sensor fusion - if (validUnit[0] && validUnit[2]) { + double gyrVecTot[3] = {0.0, 0.0, 0.0}; + if (gyr0valid && gyr2valid) { double gyr02ValuesSum[3]; VectorOperations::add(gyr0ValueBody, gyr2ValueBody, gyr02ValuesSum, 3); - VectorOperations::mulScalar(gyr02ValuesSum, .5, satRatEst, 3); - } else if ((validUnit[0] || validUnit[2]) && !(validUnit[1] || validUnit[3])) { - if (validUnit[0]) { - satRatEst = gyr0ValueBody; - } else if (validUnit[2]) { - satRatEst = gyr2ValueBody; + VectorOperations::mulScalar(gyr02ValuesSum, .5, gyrVecTot, 3); + } else if ((gyr0valid || gyr2valid) && !(gyr1valid || gyr3valid)) { + if (gyr0valid) { + std::memcpy(gyrVecTot, gyr0ValueBody, 3 * sizeof(double)); + } else if (gyr2valid) { + std::memcpy(gyrVecTot, gyr2ValueBody, 3 * sizeof(double)); } - } else if ((validUnit[1]) && (validUnit[3])) { + } else if (gyr1valid && gyr3valid) { double gyr13ValuesSum[3]; double gyr13ValuesMean[3]; VectorOperations::add(gyr1ValueBody, gyr3ValueBody, gyr13ValuesSum, 3); VectorOperations::mulScalar(gyr13ValuesSum, .5, gyr13ValuesMean, 3); - if (validUnit[0]) { - satRatEst[0] = + if (gyr0valid) { + gyrVecTot[0] = ((gyr0ValueBody[0] / gyrParameters->gyr02variance[0]) + (gyr13ValuesMean[0] / gyrParameters->gyr13variance[0])) / ((1 / gyrParameters->gyr02variance[0]) + (1 / gyrParameters->gyr13variance[0])); - satRatEst[1] = + gyrVecTot[1] = ((gyr0ValueBody[1] / gyrParameters->gyr02variance[1]) + (gyr13ValuesMean[1] / gyrParameters->gyr13variance[1])) / ((1 / gyrParameters->gyr02variance[1]) + (1 / gyrParameters->gyr13variance[1])); - satRatEst[2] = + gyrVecTot[2] = ((gyr0ValueBody[2] / gyrParameters->gyr02variance[2]) + (gyr13ValuesMean[2] / gyrParameters->gyr13variance[2])) / ((1 / gyrParameters->gyr02variance[2]) + (1 / gyrParameters->gyr13variance[2])); - } else if (validUnit[2]) { - satRatEst[0] = + } else if (gyr2valid) { + gyrVecTot[0] = ((gyr2ValueBody[0] / gyrParameters->gyr02variance[0]) + (gyr13ValuesMean[0] / gyrParameters->gyr13variance[0])) / ((1 / gyrParameters->gyr02variance[0]) + (1 / gyrParameters->gyr13variance[0])); - satRatEst[1] = + gyrVecTot[1] = ((gyr2ValueBody[1] / gyrParameters->gyr02variance[1]) + (gyr13ValuesMean[1] / gyrParameters->gyr13variance[1])) / ((1 / gyrParameters->gyr02variance[1]) + (1 / gyrParameters->gyr13variance[1])); - satRatEst[2] = + gyrVecTot[2] = ((gyr2ValueBody[2] / gyrParameters->gyr02variance[2]) + (gyr13ValuesMean[2] / gyrParameters->gyr13variance[2])) / ((1 / gyrParameters->gyr02variance[2]) + (1 / gyrParameters->gyr13variance[2])); - } else - satRatEst = gyr13ValuesMean; - } else if (validUnit[1]) { - satRatEst = gyr1ValueBody; - } else if (validUnit[3]) { - satRatEst = gyr3ValueBody; + } else { + std::memcpy(gyrVecTot, gyr13ValuesMean, 3 * sizeof(double)); + } + } else if (gyr1valid) { + std::memcpy(gyrVecTot, gyr1ValueBody, 3 * sizeof(double)); + } else if (gyr3valid) { + std::memcpy(gyrVecTot, gyr3ValueBody, 3 * sizeof(double)); + } + { + PoolReadGuard pg(gyrDataProcessed); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(gyrDataProcessed->gyr0vec.value, gyr0ValueBody, 3 * sizeof(double)); + gyrDataProcessed->gyr0vec.setValid(gyr0valid); + std::memcpy(gyrDataProcessed->gyr1vec.value, gyr1ValueBody, 3 * sizeof(double)); + std::memcpy(gyrDataProcessed->gyr2vec.value, gyr2ValueBody, 3 * sizeof(double)); + std::memcpy(gyrDataProcessed->gyr3vec.value, gyr3ValueBody, 3 * sizeof(double)); + std::memcpy(gyrDataProcessed->gyrVecTot.value, gyrVecTot, 3 * sizeof(double)); + gyrDataProcessed->setValidity(true, false); + } } - *satRateEstValid = true; } void SensorProcessing::processGps(const double gps0latitude, const double gps0longitude, - const bool validGps, double *gcLatitude, double *gdLongitude) { + const bool validGps, + acsctrl::GpsDataProcessed *gpsDataProcessed) { // name to convert not process + double gdLongitude, gcLatitude; if (validGps) { // Transforming from Degree to Radians and calculation geocentric lattitude from geodetic - *gdLongitude = gps0longitude * PI / 180; + gdLongitude = gps0longitude * PI / 180; double latitudeRad = gps0latitude * PI / 180; double eccentricityWgs84 = 0.0818195; double factor = 1 - pow(eccentricityWgs84, 2); - *gcLatitude = atan(factor * tan(latitudeRad)); - validGcLatitude = true; + gcLatitude = atan(factor * tan(latitudeRad)); + // validGcLatitude = true; + } + { + PoolReadGuard pg(gpsDataProcessed); + if (pg.getReadResult() == returnvalue::OK) { + gpsDataProcessed->gdLongitude.value = gdLongitude; + gpsDataProcessed->gcLatitude.value = gcLatitude; + gpsDataProcessed->setValidity(validGps, validGps); + if (!validGps) { + gpsDataProcessed->gdLongitude.value = 0.0; + gpsDataProcessed->gcLatitude.value = 0.0; + } + } } } void SensorProcessing::process(timeval now, ACS::SensorValues *sensorValues, - ACS::OutputValues *outputValues, + acsctrl::MgmDataProcessed *mgmDataProcessed, + acsctrl::SusDataProcessed *susDataProcessed, + acsctrl::GyrDataProcessed *gyrDataProcessed, + acsctrl::GpsDataProcessed *gpsDataProcessed, const AcsParameters *acsParameters) { sensorValues->update(); processGps(sensorValues->gpsSet.latitude.value, sensorValues->gpsSet.longitude.value, - sensorValues->gpsSet.isValid(), &outputValues->gcLatitude, &outputValues->gdLongitude); + sensorValues->gpsSet.isValid(), gpsDataProcessed); - outputValues->mgmUpdated = processMgm( - sensorValues->mgm0Lis3Set.fieldStrengths.value, - sensorValues->mgm0Lis3Set.fieldStrengths.isValid(), - sensorValues->mgm1Rm3100Set.fieldStrengths.value, - sensorValues->mgm1Rm3100Set.fieldStrengths.isValid(), - sensorValues->mgm2Lis3Set.fieldStrengths.value, - sensorValues->mgm2Lis3Set.fieldStrengths.isValid(), - sensorValues->mgm3Rm3100Set.fieldStrengths.value, - sensorValues->mgm3Rm3100Set.fieldStrengths.isValid(), sensorValues->imtqMgmSet.mtmRawNt.value, - sensorValues->imtqMgmSet.mtmRawNt.isValid(), now, &acsParameters->mgmHandlingParameters, - outputValues->gcLatitude, outputValues->gdLongitude, sensorValues->gpsSet.altitude.value, - sensorValues->gpsSet.isValid(), outputValues->magFieldEst, &outputValues->magFieldEstValid, - outputValues->magFieldModel, &outputValues->magFieldModelValid, - outputValues->magneticFieldVectorDerivative, - &outputValues->magneticFieldVectorDerivativeValid); // VALID outputs- PoolVariable ? + processMgm(sensorValues->mgm0Lis3Set.fieldStrengths.value, + sensorValues->mgm0Lis3Set.fieldStrengths.isValid(), + sensorValues->mgm1Rm3100Set.fieldStrengths.value, + sensorValues->mgm1Rm3100Set.fieldStrengths.isValid(), + sensorValues->mgm2Lis3Set.fieldStrengths.value, + sensorValues->mgm2Lis3Set.fieldStrengths.isValid(), + sensorValues->mgm3Rm3100Set.fieldStrengths.value, + sensorValues->mgm3Rm3100Set.fieldStrengths.isValid(), + sensorValues->imtqMgmSet.mtmRawNt.value, sensorValues->imtqMgmSet.mtmRawNt.isValid(), + now, &acsParameters->mgmHandlingParameters, gpsDataProcessed, + sensorValues->gpsSet.altitude.value, sensorValues->gpsSet.isValid(), mgmDataProcessed); processSus(sensorValues->susSets[0].channels.value, sensorValues->susSets[0].channels.isValid(), sensorValues->susSets[1].channels.value, sensorValues->susSets[1].channels.isValid(), @@ -507,10 +630,7 @@ void SensorProcessing::process(timeval now, ACS::SensorValues *sensorValues, sensorValues->susSets[10].channels.value, sensorValues->susSets[10].channels.isValid(), sensorValues->susSets[11].channels.value, sensorValues->susSets[11].channels.isValid(), now, &acsParameters->susHandlingParameters, &acsParameters->sunModelParameters, - outputValues->sunDirEst, &outputValues->sunDirEstValid, outputValues->sunDirModel, - &outputValues->sunDirModelValid, outputValues->sunVectorDerivative, - &outputValues->sunVectorDerivativeValid); - // VALID outputs ? + susDataProcessed); processGyr( sensorValues->gyr0AdisSet.angVelocX.value, sensorValues->gyr0AdisSet.angVelocX.isValid(), @@ -525,6 +645,5 @@ void SensorProcessing::process(timeval now, ACS::SensorValues *sensorValues, sensorValues->gyr3L3gSet.angVelocX.value, sensorValues->gyr3L3gSet.angVelocX.isValid(), sensorValues->gyr3L3gSet.angVelocY.value, sensorValues->gyr3L3gSet.angVelocY.isValid(), sensorValues->gyr3L3gSet.angVelocZ.value, sensorValues->gyr3L3gSet.angVelocZ.isValid(), now, - &acsParameters->gyrHandlingParameters, outputValues->satRateEst, - &outputValues->satRateEstValid); + &acsParameters->gyrHandlingParameters, gyrDataProcessed); } diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h index 50b78238..11d2ebeb 100644 --- a/mission/controller/acs/SensorProcessing.h +++ b/mission/controller/acs/SensorProcessing.h @@ -23,19 +23,21 @@ class SensorProcessing { SensorProcessing(AcsParameters *acsParameters_); virtual ~SensorProcessing(); - void process(timeval now, ACS::SensorValues *sensorValues, ACS::OutputValues *outputValues, + void process(timeval now, ACS::SensorValues *sensorValues, + acsctrl::MgmDataProcessed *mgmDataProcessed, + acsctrl::SusDataProcessed *susDataProcessed, + acsctrl::GyrDataProcessed *gyrDataProcessed, + acsctrl::GpsDataProcessed *gpsDataProcessed, const AcsParameters *acsParameters); // Will call protected functions private: protected: // short description needed for every function - bool processMgm(const float *mgm0Value, bool mgm0valid, const float *mgm1Value, bool mgm1valid, + void processMgm(const float *mgm0Value, bool mgm0valid, const float *mgm1Value, bool mgm1valid, const float *mgm2Value, bool mgm2valid, const float *mgm3Value, bool mgm3valid, const float *mgm4Value, bool mgm4valid, timeval timeOfMgmMeasurement, const AcsParameters::MgmHandlingParameters *mgmParameters, - const double gpsLatitude, const double gpsLongitude, const double gpsAltitude, - bool gpsValid, double *magFieldEst, bool *outputValid, double *magFieldModel, - bool *magFieldModelValid, double *magneticFieldVectorDerivative, - bool *magneticFieldVectorDerivativeValid); // Output + acsctrl::GpsDataProcessed *gpsDataProcessed, const double gpsAltitude, + bool gpsValid, acsctrl::MgmDataProcessed *mgmDataProcessed); void processSus(const uint16_t *sus0Value, bool sus0valid, const uint16_t *sus1Value, bool sus1valid, const uint16_t *sus2Value, bool sus2valid, @@ -47,9 +49,8 @@ class SensorProcessing { bool sus10valid, const uint16_t *sus11Value, bool sus11valid, timeval timeOfSusMeasurement, const AcsParameters::SusHandlingParameters *susParameters, - const AcsParameters::SunModelParameters *sunModelParameters, double *sunDirEst, - bool *sunDirEstValid, double *sunVectorInertial, bool *sunVectorInertialValid, - double *sunVectorDerivative, bool *sunVectorDerivativeValid); + const AcsParameters::SunModelParameters *sunModelParameters, + acsctrl::SusDataProcessed *susDataProcessed); void processGyr(const double gyr0axXvalue, bool gyr0axXvalid, const double gyr0axYvalue, bool gyr0axYvalid, const double gyr0axZvalue, bool gyr0axZvalid, @@ -60,21 +61,23 @@ class SensorProcessing { const double gyr3axXvalue, bool gyr3axXvalid, const double gyr3axYvalue, bool gyr3axYvalid, const double gyr3axZvalue, bool gyr3axZvalid, timeval timeOfGyrMeasurement, - const AcsParameters::GyrHandlingParameters *gyrParameters, double *satRatEst, - bool *satRateEstValid); + const AcsParameters::GyrHandlingParameters *gyrParameters, + acsctrl::GyrDataProcessed *gyrDataProcessed); void processStr(); void processGps(const double gps0latitude, const double gps0longitude, const bool validGps, - double *gcLatitude, double *gdLongitude); + acsctrl::GpsDataProcessed *gpsDataProcessed); - double savedMagFieldEst[3]; + double savedMgmVecTot[3]; timeval timeOfSavedMagFieldEst; - double savedSunVector[3]; + double savedSusVecTot[3]; timeval timeOfSavedSusDirEst; bool validMagField; bool validGcLatitude; + const float zeroVector[3] = {0.0, 0.0, 0.0}; + SusConverter susConverter; AcsParameters acsParameters; }; -- 2.34.1 From a13ccb43d23df5bbfb5b18162f24a8ddd5a36092 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 3 Nov 2022 10:43:27 +0100 Subject: [PATCH 077/101] removed OutputValues amended sumbode list inserted writes to output DataPools --- mission/controller/AcsController.cpp | 166 +++++++++++---- mission/controller/AcsController.h | 18 +- mission/controller/acs/ActuatorCmd.cpp | 50 +++-- mission/controller/acs/ActuatorCmd.h | 56 +++-- mission/controller/acs/CMakeLists.txt | 1 - mission/controller/acs/Guidance.cpp | 40 ++-- mission/controller/acs/Guidance.h | 42 ++-- mission/controller/acs/Igrf13Model.cpp | 194 +++++++++--------- mission/controller/acs/Igrf13Model.h | 170 +++++++-------- .../acs/MultiplicativeKalmanFilter.cpp | 86 +++++--- .../acs/MultiplicativeKalmanFilter.h | 21 +- mission/controller/acs/Navigation.cpp | 34 +-- mission/controller/acs/Navigation.h | 32 +-- mission/controller/acs/OutputValues.cpp | 9 - mission/controller/acs/OutputValues.h | 44 ---- mission/controller/acs/SensorProcessing.h | 1 - mission/controller/acs/SensorValues.cpp | 1 - mission/controller/acs/control/Detumble.cpp | 45 ++-- mission/controller/acs/control/Detumble.h | 10 +- mission/controller/acs/control/PtgCtrl.cpp | 2 +- mission/controller/acs/control/PtgCtrl.h | 3 +- mission/controller/acs/control/SafeCtrl.cpp | 41 ++-- mission/controller/acs/control/SafeCtrl.h | 17 +- .../AcsCtrlDefinitions.h | 29 ++- 24 files changed, 590 insertions(+), 522 deletions(-) delete mode 100644 mission/controller/acs/OutputValues.cpp delete mode 100644 mission/controller/acs/OutputValues.h diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 0cb4f330..953a91a1 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -20,6 +20,7 @@ AcsController::AcsController(object_id_t objectId) gyrDataProcessed(this), gpsDataProcessed(this), mekfData(this), + ctrlValData(this), actuatorCmdData(this) {} ReturnValue_t AcsController::handleCommandMessage(CommandMessage *message) { @@ -48,7 +49,9 @@ void AcsController::performControlOperation() { case SUBMODE_DETUMBLE: performDetumble(); break; - case SUBMODE_PTG_GS: + case SUBMODE_PTG_TARGET: + case SUBMODE_PTG_NADIR: + case SUBMODE_PTG_INERTIAL: performPointingCtrl(); break; } @@ -80,7 +83,7 @@ void AcsController::performControlOperation() { // DEBUG : REMOVE AFTER COMPLETION mode = MODE_ON; - submode = SUBMODE_DETUMBLE; + submode = SUBMODE_SAFE; // DEBUG END } @@ -90,7 +93,6 @@ void AcsController::performSafe() { // another place since we have to do it for every mode regardless of safe or not ACS::SensorValues sensorValues; - ACS::OutputValues outputValues; timeval now; Clock::getClock_timeval(&now); @@ -98,38 +100,54 @@ void AcsController::performSafe() { sensorProcessing.process(now, &sensorValues, &mgmDataProcessed, &susDataProcessed, &gyrDataProcessed, &gpsDataProcessed, &acsParameters); ReturnValue_t validMekf; - navigation.useMekf(&sensorValues, &outputValues, &validMekf); + navigation.useMekf(&sensorValues, &gyrDataProcessed, &mgmDataProcessed, &susDataProcessed, + &mekfData, &validMekf); // Give desired satellite rate and sun direction to align double satRateSafe[3] = {0, 0, 0}, sunTargetDir[3] = {0, 0, 0}; guidance.getTargetParamsSafe(sunTargetDir, satRateSafe); // IF MEKF is working - double magMomMtq[3] = {0, 0, 0}; + double magMomMtq[3] = {0, 0, 0}, errAng = 0.0; bool magMomMtqValid = false; if (validMekf == returnvalue::OK) { - safeCtrl.safeMekf(now, (outputValues.quatMekfBJ), &(outputValues.quatMekfBJValid), - (outputValues.magFieldModel), &(outputValues.magFieldModelValid), - (outputValues.sunDirModel), &(outputValues.sunDirModelValid), - (outputValues.satRateMekf), &(outputValues.satRateMekfValid), sunTargetDir, - satRateSafe, magMomMtq, &magMomMtqValid); + safeCtrl.safeMekf(now, mekfData.quatMekf.value, mekfData.quatMekf.isValid(), + mgmDataProcessed.magIgrfModel.value, mgmDataProcessed.magIgrfModel.isValid(), + susDataProcessed.sunIjkModel.value, susDataProcessed.isValid(), + mekfData.satRotRateMekf.value, mekfData.satRotRateMekf.isValid(), + sunTargetDir, satRateSafe, &errAng, magMomMtq, &magMomMtqValid); } else { - safeCtrl.safeNoMekf(now, outputValues.sunDirEst, &outputValues.sunDirEstValid, - outputValues.sunVectorDerivative, &(outputValues.sunVectorDerivativeValid), - outputValues.magFieldEst, &(outputValues.magFieldEstValid), - outputValues.magneticFieldVectorDerivative, - &(outputValues.magneticFieldVectorDerivativeValid), sunTargetDir, - satRateSafe, magMomMtq, &magMomMtqValid); + safeCtrl.safeNoMekf( + now, susDataProcessed.susVecTot.value, susDataProcessed.susVecTot.isValid(), + susDataProcessed.susVecTotDerivative.value, susDataProcessed.susVecTotDerivative.isValid(), + mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTot.isValid(), + mgmDataProcessed.mgmVecTotDerivative.value, mgmDataProcessed.mgmVecTotDerivative.isValid(), + sunTargetDir, satRateSafe, &errAng, magMomMtq, &magMomMtqValid); } double dipolCmdUnits[3] = {0, 0, 0}; actuatorCmd.cmdDipolMtq(magMomMtq, dipolCmdUnits); + { + PoolReadGuard pg(&ctrlValData); + if (pg.getReadResult() == returnvalue::OK) { + double zeroQuat[4] = {0, 0, 0, 0}; + std::memcpy(ctrlValData.tgtQuat.value, zeroQuat, 4 * sizeof(double)); + ctrlValData.tgtQuat.setValid(false); + std::memcpy(ctrlValData.errQuat.value, zeroQuat, 4 * sizeof(double)); + ctrlValData.errQuat.setValid(false); + ctrlValData.errAng.value = errAng; + ctrlValData.errAng.setValid(true); + ctrlValData.setValidity(true, false); + } + } + // Detumble check and switch - if (outputValues.satRateMekfValid && VectorOperations::norm(outputValues.satRateMekf, 3) > - acsParameters.detumbleParameter.omegaDetumbleStart) { + if (mekfData.satRotRateMekf.isValid() && + VectorOperations::norm(mekfData.satRotRateMekf.value, 3) > + acsParameters.detumbleParameter.omegaDetumbleStart) { detumbleCounter++; - } else if (outputValues.satRateEstValid && - VectorOperations::norm(outputValues.satRateEst, 3) > + } else if (gyrDataProcessed.gyrVecTot.isValid() && + VectorOperations::norm(gyrDataProcessed.gyrVecTot.value, 3) > acsParameters.detumbleParameter.omegaDetumbleStart) { detumbleCounter++; } else { @@ -139,12 +157,31 @@ void AcsController::performSafe() { submode = SUBMODE_DETUMBLE; detumbleCounter = 0; } - // commanding.magnetorquesDipol(); + + { + PoolReadGuard pg(&actuatorCmdData); + if (pg.getReadResult() == returnvalue::OK) { + double zeroVec[3] = {0, 0, 0, 0}; + std::memcpy(actuatorCmdData.rwTargetTorque.value, zeroVec, 4 * sizeof(double)); + actuatorCmdData.rwTargetTorque.setValid(false); + std::memcpy(actuatorCmdData.rwTargetSpeed.value, zeroVec, 4 * sizeof(double)); + actuatorCmdData.rwTargetSpeed.setValid(false); + std::memcpy(actuatorCmdData.mtqTargetDipole.value, dipolCmdUnits, 3 * sizeof(double)); + actuatorCmdData.mtqTargetDipole.setValid(true); + actuatorCmdData.setValidity(true, false); + } + } + // { + // PoolReadGuard pg(&dipoleSet); + // MutexGuard mg(torquer::lazyLock()); + // torquer::NEW_ACTUATION_FLAG = true; + // dipoleSet.setDipoles(dipolCmdUnits[0], dipolCmdUnits[1], dipolCmdUnits[2], + //torqueDuration); + // } } void AcsController::performDetumble() { ACS::SensorValues sensorValues; - ACS::OutputValues outputValues; timeval now; Clock::getClock_timeval(&now); @@ -152,20 +189,22 @@ void AcsController::performDetumble() { sensorProcessing.process(now, &sensorValues, &mgmDataProcessed, &susDataProcessed, &gyrDataProcessed, &gpsDataProcessed, &acsParameters); ReturnValue_t validMekf; - navigation.useMekf(&sensorValues, &outputValues, &validMekf); + navigation.useMekf(&sensorValues, &gyrDataProcessed, &mgmDataProcessed, &susDataProcessed, + &mekfData, &validMekf); double magMomMtq[3] = {0, 0, 0}; - detumble.bDotLaw(outputValues.magneticFieldVectorDerivative, - &outputValues.magneticFieldVectorDerivativeValid, outputValues.magFieldEst, - &outputValues.magFieldEstValid, magMomMtq); + detumble.bDotLaw(mgmDataProcessed.mgmVecTotDerivative.value, + mgmDataProcessed.mgmVecTotDerivative.isValid(), mgmDataProcessed.mgmVecTot.value, + mgmDataProcessed.mgmVecTot.isValid(), magMomMtq); double dipolCmdUnits[3] = {0, 0, 0}; actuatorCmd.cmdDipolMtq(magMomMtq, dipolCmdUnits); - if (outputValues.satRateMekfValid && VectorOperations::norm(outputValues.satRateMekf, 3) < - acsParameters.detumbleParameter.omegaDetumbleEnd) { + if (mekfData.satRotRateMekf.isValid() && + VectorOperations::norm(mekfData.satRotRateMekf.value, 3) < + acsParameters.detumbleParameter.omegaDetumbleEnd) { detumbleCounter++; - } else if (outputValues.satRateEstValid && - VectorOperations::norm(outputValues.satRateEst, 3) < + } else if (gyrDataProcessed.gyrVecTot.isValid() && + VectorOperations::norm(gyrDataProcessed.gyrVecTot.value, 3) < acsParameters.detumbleParameter.omegaDetumbleEnd) { detumbleCounter++; } else { @@ -175,11 +214,31 @@ void AcsController::performDetumble() { submode = SUBMODE_SAFE; detumbleCounter = 0; } + + { + PoolReadGuard pg(&actuatorCmdData); + if (pg.getReadResult() == returnvalue::OK) { + double zeroVec[3] = {0, 0, 0, 0}; + std::memcpy(actuatorCmdData.rwTargetTorque.value, zeroVec, 4 * sizeof(double)); + actuatorCmdData.rwTargetTorque.setValid(false); + std::memcpy(actuatorCmdData.rwTargetSpeed.value, zeroVec, 4 * sizeof(double)); + actuatorCmdData.rwTargetSpeed.setValid(false); + std::memcpy(actuatorCmdData.mtqTargetDipole.value, dipolCmdUnits, 3 * sizeof(double)); + actuatorCmdData.mtqTargetDipole.setValid(true); + actuatorCmdData.setValidity(true, false); + } + } + // { + // PoolReadGuard pg(&dipoleSet); + // MutexGuard mg(torquer::lazyLock()); + // torquer::NEW_ACTUATION_FLAG = true; + // dipoleSet.setDipoles(dipolCmdUnits[0], dipolCmdUnits[1], dipolCmdUnits[2], + // torqueDuration); + // } } void AcsController::performPointingCtrl() { ACS::SensorValues sensorValues; - ACS::OutputValues outputValues; timeval now; Clock::getClock_timeval(&now); @@ -187,12 +246,14 @@ void AcsController::performPointingCtrl() { sensorProcessing.process(now, &sensorValues, &mgmDataProcessed, &susDataProcessed, &gyrDataProcessed, &gpsDataProcessed, &acsParameters); ReturnValue_t validMekf; - navigation.useMekf(&sensorValues, &outputValues, &validMekf); + navigation.useMekf(&sensorValues, &gyrDataProcessed, &mgmDataProcessed, &susDataProcessed, + &mekfData, &validMekf); double targetQuat[4] = {0, 0, 0, 0}, refSatRate[3] = {0, 0, 0}; - guidance.targetQuatPtg(&sensorValues, &outputValues, now, targetQuat, refSatRate); - double quatError[3] = {0, 0, 0}, deltaRate[3] = {0, 0, 0}; - guidance.comparePtg(targetQuat, &outputValues, refSatRate, quatError, deltaRate); + guidance.targetQuatPtg(&sensorValues, &mekfData, &susDataProcessed, now, targetQuat, refSatRate); + double quatErrorComplete[4] = {0, 0, 0, 0}, quatError[3] = {0, 0, 0}, + deltaRate[3] = {0, 0, 0}; // ToDo: check if pointer needed + guidance.comparePtg(targetQuat, &mekfData, refSatRate, quatErrorComplete, quatError, deltaRate); double rwPseudoInv[4][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; guidance.getDistributionMatrixRw(&sensorValues, *rwPseudoInv); double torquePtgRws[4] = {0, 0, 0, 0}, mode = 0; @@ -207,11 +268,29 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), torquePtgRws, rwTrqNs, cmdSpeedRws); double mgtDpDes[3] = {0, 0, 0}, dipolUnits[3] = {0, 0, 0}; // Desaturation Dipol - ptgCtrl.ptgDesaturation( - outputValues.magFieldEst, &outputValues.magFieldEstValid, outputValues.satRateMekf, - &(sensorValues.rw1Set.currSpeed.value), &(sensorValues.rw2Set.currSpeed.value), - &(sensorValues.rw3Set.currSpeed.value), &(sensorValues.rw4Set.currSpeed.value), mgtDpDes); + ptgCtrl.ptgDesaturation(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); actuatorCmd.cmdDipolMtq(mgtDpDes, dipolUnits); + + { + PoolReadGuard pg(&actuatorCmdData); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(actuatorCmdData.rwTargetTorque.value, rwTrqNs, 4 * sizeof(double)); + std::memcpy(actuatorCmdData.rwTargetSpeed.value, cmdSpeedRws, 4 * sizeof(double)); + std::memcpy(actuatorCmdData.mtqTargetDipole.value, dipolUnits, 3 * sizeof(double)); + actuatorCmdData.setValidity(true, true); + } + } + // { + // PoolReadGuard pg(&dipoleSet); + // MutexGuard mg(torquer::lazyLock()); + // torquer::NEW_ACTUATION_FLAG = true; + // dipoleSet.setDipoles(dipolCmdUnits[0], dipolCmdUnits[1], dipolCmdUnits[2], + // torqueDuration); + // } } ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, @@ -286,6 +365,11 @@ ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localD localDataPoolMap.emplace(acsctrl::PoolIds::QUAT_MEKF, &quatMekf); localDataPoolMap.emplace(acsctrl::PoolIds::SAT_ROT_RATE_MEKF, &satRotRateMekf); poolManager.subscribeForRegularPeriodicPacket({mekfData.getSid(), false, 5.0}); + // Ctrl Values + localDataPoolMap.emplace(acsctrl::PoolIds::TGT_QUAT, &tgtQuat); + localDataPoolMap.emplace(acsctrl::PoolIds::ERROR_QUAT, &errQuat); + localDataPoolMap.emplace(acsctrl::PoolIds::ERROR_ANG, &errAng); + poolManager.subscribeForRegularPeriodicPacket({ctrlValData.getSid(), false, 5.0}); // Actuator CMD localDataPoolMap.emplace(acsctrl::PoolIds::RW_TARGET_TORQUE, &rwTargetTorque); localDataPoolMap.emplace(acsctrl::PoolIds::RW_TARGET_SPEED, &rwTargetSpeed); @@ -312,6 +396,8 @@ LocalPoolDataSetBase *AcsController::getDataSetHandle(sid_t sid) { return &gpsDataProcessed; case acsctrl::MEKF_DATA: return &mekfData; + case acsctrl::CTRL_VAL_DATA: + return &ctrlValData; case acsctrl::ACTUATOR_CMD_DATA: return &actuatorCmdData; default: @@ -328,7 +414,7 @@ ReturnValue_t AcsController::checkModeCommand(Mode_t mode, Submode_t submode, return INVALID_SUBMODE; } } else if ((mode == MODE_ON) || (mode == MODE_NORMAL)) { - if ((submode > 5) || (submode < 2)) { + if ((submode > 6) || (submode < 2)) { return INVALID_SUBMODE; } else { return returnvalue::OK; diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index dcd78621..18c8d824 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -8,7 +8,6 @@ #include "acs/ActuatorCmd.h" #include "acs/Guidance.h" #include "acs/Navigation.h" -#include "acs/OutputValues.h" #include "acs/SensorProcessing.h" #include "acs/control/Detumble.h" #include "acs/control/PtgCtrl.h" @@ -27,8 +26,9 @@ class AcsController : public ExtendedControllerBase { static const Submode_t SUBMODE_SAFE = 2; static const Submode_t SUBMODE_DETUMBLE = 3; - static const Submode_t SUBMODE_PTG_GS = 4; + static const Submode_t SUBMODE_PTG_TARGET = 4; static const Submode_t SUBMODE_PTG_NADIR = 5; + static const Submode_t SUBMODE_PTG_INERTIAL = 6; protected: void performSafe(); @@ -83,7 +83,7 @@ class AcsController : public ExtendedControllerBase { PoolEntry mgm3VecProc = PoolEntry(3); PoolEntry mgm4VecProc = PoolEntry(3); PoolEntry mgmVecTot = PoolEntry(3); - PoolEntry mgmVecTotDer = PoolEntry(3); + PoolEntry mgmVecTotDer = PoolEntry(3); PoolEntry magIgrf = PoolEntry(3); // SUSs @@ -115,9 +115,9 @@ class AcsController : public ExtendedControllerBase { PoolEntry sus9VecProc = PoolEntry(3); PoolEntry sus10VecProc = PoolEntry(3); PoolEntry sus11VecProc = PoolEntry(3); - PoolEntry susVecTot = PoolEntry(3); - PoolEntry susVecTotDer = PoolEntry(3); - PoolEntry sunIjk = PoolEntry(3); + PoolEntry susVecTot = PoolEntry(3); + PoolEntry susVecTotDer = PoolEntry(3); + PoolEntry sunIjk = PoolEntry(3); // GYRs acsctrl::GyrDataRaw gyrDataRaw; @@ -144,6 +144,12 @@ class AcsController : public ExtendedControllerBase { PoolEntry quatMekf = PoolEntry(4); PoolEntry satRotRateMekf = PoolEntry(3); + // Ctrl Values + acsctrl::CtrlValData ctrlValData; + PoolEntry tgtQuat = PoolEntry(4); + PoolEntry errQuat = PoolEntry(4); + PoolEntry errAng = PoolEntry(); + // Actuator CMD acsctrl::ActuatorCmdData actuatorCmdData; PoolEntry rwTargetTorque = PoolEntry(4); diff --git a/mission/controller/acs/ActuatorCmd.cpp b/mission/controller/acs/ActuatorCmd.cpp index 0dba2016..2a0a9425 100644 --- a/mission/controller/acs/ActuatorCmd.cpp +++ b/mission/controller/acs/ActuatorCmd.cpp @@ -5,23 +5,21 @@ * Author: Robin Marquardt */ - #include "ActuatorCmd.h" -#include "util/MathOperations.h" -#include "util/CholeskyDecomposition.h" -#include + #include -#include #include #include +#include -ActuatorCmd::ActuatorCmd(AcsParameters *acsParameters_) { - acsParameters = *acsParameters_; -} +#include -ActuatorCmd::~ActuatorCmd(){ +#include "util/CholeskyDecomposition.h" +#include "util/MathOperations.h" -} +ActuatorCmd::ActuatorCmd(AcsParameters *acsParameters_) { acsParameters = *acsParameters_; } + +ActuatorCmd::~ActuatorCmd() {} void ActuatorCmd::cmdSpeedToRws(const int32_t *speedRw0, const int32_t *speedRw1, const int32_t *speedRw2, const int32_t *speedRw3, @@ -57,22 +55,20 @@ void ActuatorCmd::cmdSpeedToRws(const int32_t *speedRw0, const int32_t *speedRw1 } void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, double *dipolMomentUnits) { + // Convert to Unit frame + MatrixOperations::multiply(*acsParameters.magnetorquesParameter.inverseAlignment, + dipolMoment, dipolMomentUnits, 3, 3, 1); + // Scaling along largest element if dipol exceeds maximum + double maxDipol = acsParameters.magnetorquesParameter.DipolMax; + double maxValue = 0; + for (int i = 0; i < 3; i++) { + if (abs(dipolMomentUnits[i]) > maxDipol) { + maxValue = abs(dipolMomentUnits[i]); + } + } -// Convert to Unit frame - MatrixOperations::multiply(*acsParameters.magnetorquesParameter.inverseAlignment, dipolMoment, dipolMomentUnits, 3, 3, 1); -// Scaling along largest element if dipol exceeds maximum - double maxDipol = acsParameters.magnetorquesParameter.DipolMax; - double maxValue = 0; - for (int i = 0; i < 3; i++) { - if (abs(dipolMomentUnits[i]) > maxDipol) { - maxValue = abs(dipolMomentUnits[i]); - } - } - - if (maxValue > maxDipol) { - - double scalingFactor = maxDipol / maxValue; - VectorOperations::mulScalar(dipolMomentUnits, scalingFactor, dipolMomentUnits, 3); - - } + if (maxValue > maxDipol) { + double scalingFactor = maxDipol / maxValue; + VectorOperations::mulScalar(dipolMomentUnits, scalingFactor, dipolMomentUnits, 3); + } } diff --git a/mission/controller/acs/ActuatorCmd.h b/mission/controller/acs/ActuatorCmd.h index 1da2c89a..5cb3ff00 100644 --- a/mission/controller/acs/ActuatorCmd.h +++ b/mission/controller/acs/ActuatorCmd.h @@ -8,42 +8,40 @@ #ifndef ACTUATORCMD_H_ #define ACTUATORCMD_H_ - #include "AcsParameters.h" -#include "SensorProcessing.h" #include "MultiplicativeKalmanFilter.h" +#include "SensorProcessing.h" #include "SensorValues.h" -#include "OutputValues.h" -class ActuatorCmd{ -public: - ActuatorCmd(AcsParameters *acsParameters_); //Input mode ? - virtual ~ActuatorCmd(); +class ActuatorCmd { + public: + ActuatorCmd(AcsParameters *acsParameters_); // Input mode ? + virtual ~ActuatorCmd(); - /* - * @brief: cmdSpeedToRws() will set the maximum possible torque for the reaction wheels, also - * will calculate the needed revolutions per minute for the RWs, which will be given - * as Input to the RWs - * @param: rwTrqIn given torque from pointing controller - * rwTrqNS Nullspace torque - * 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 *rwTrqIn, - const double *rwTrqNS, double *rwCmdSpeed); + /* + * @brief: cmdSpeedToRws() will set the maximum possible torque for the reaction + * wheels, also will calculate the needed revolutions per minute for the RWs, which will be given + * as Input to the RWs + * @param: rwTrqIn given torque from pointing controller + * rwTrqNS Nullspace torque + * 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 *rwTrqIn, const double *rwTrqNS, + double *rwCmdSpeed); - /* - * @brief: cmdDipolMtq() gives the commanded dipol moment for the magnetorques - * - * @param: dipolMoment given dipol moment in spacecraft frame - * dipolMomentUnits resulting dipol moment for every unit - */ - void cmdDipolMtq(const double *dipolMoment, double *dipolMomentUnits); + /* + * @brief: cmdDipolMtq() gives the commanded dipol moment for the magnetorques + * + * @param: dipolMoment given dipol moment in spacecraft frame + * dipolMomentUnits resulting dipol moment for every unit + */ + void cmdDipolMtq(const double *dipolMoment, double *dipolMomentUnits); -protected: - -private: - AcsParameters acsParameters; + protected: + private: + AcsParameters acsParameters; }; #endif /* ACTUATORCMD_H_ */ diff --git a/mission/controller/acs/CMakeLists.txt b/mission/controller/acs/CMakeLists.txt index c949a067..a379197d 100644 --- a/mission/controller/acs/CMakeLists.txt +++ b/mission/controller/acs/CMakeLists.txt @@ -6,7 +6,6 @@ target_sources( Igrf13Model.cpp MultiplicativeKalmanFilter.cpp Navigation.cpp - OutputValues.cpp SensorProcessing.cpp SensorValues.cpp SusConverter.cpp) diff --git a/mission/controller/acs/Guidance.cpp b/mission/controller/acs/Guidance.cpp index f6ebee5f..35a7295a 100644 --- a/mission/controller/acs/Guidance.cpp +++ b/mission/controller/acs/Guidance.cpp @@ -7,6 +7,7 @@ #include "Guidance.h" +#include #include #include #include @@ -29,8 +30,9 @@ void Guidance::getTargetParamsSafe(double sunTargetSafe[3], double satRateSafe[3 // memcpy(sunTargetSafe, acsParameters.safeModeControllerParameters.sunTargetDir, 24); } -void Guidance::targetQuatPtg(ACS::SensorValues *sensorValues, ACS::OutputValues *outputValues, - timeval now, double targetQuat[4], double refSatRate[3]) { +void Guidance::targetQuatPtg(ACS::SensorValues *sensorValues, acsctrl::MekfData *mekfData, + acsctrl::SusDataProcessed *susDataProcessed, timeval now, + double targetQuat[4], double refSatRate[3]) { //------------------------------------------------------------------------------------- // Calculation of target quaternion to groundstation //------------------------------------------------------------------------------------- @@ -77,10 +79,8 @@ void Guidance::targetQuatPtg(ACS::SensorValues *sensorValues, ACS::OutputValues double dcmBJ[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; double dcmBE[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; double quatBJ[4] = {0, 0, 0, 0}; - quatBJ[0] = outputValues->quatMekfBJ[0]; - quatBJ[1] = outputValues->quatMekfBJ[1]; - quatBJ[2] = outputValues->quatMekfBJ[2]; - quatBJ[3] = outputValues->quatMekfBJ[3]; + std::memcpy(quatBJ, mekfData->quatMekf.value, 4 * sizeof(double)); + QuaternionOperations::toDcm(quatBJ, dcmBJ); MatrixOperations::multiply(*dcmBJ, *dcmJE, *dcmBE, 3, 3, 3); @@ -137,23 +137,16 @@ void Guidance::targetQuatPtg(ACS::SensorValues *sensorValues, ACS::OutputValues double sunDirJ[3] = {0, 0, 0}; double sunDirB[3] = {0, 0, 0}; - if (outputValues->sunDirModelValid) { - sunDirJ[0] = outputValues->sunDirModel[0]; - sunDirJ[1] = outputValues->sunDirModel[1]; - sunDirJ[2] = outputValues->sunDirModel[2]; + if (susDataProcessed->sunIjkModel.isValid()) { + std::memcpy(sunDirJ, susDataProcessed->sunIjkModel.value, 3 * sizeof(double)); MatrixOperations::multiply(*dcmBJ, sunDirJ, sunDirB, 3, 3, 1); - } - - else { - sunDirB[0] = outputValues->sunDirEst[0]; - sunDirB[1] = outputValues->sunDirEst[1]; - sunDirB[2] = outputValues->sunDirEst[2]; + } else { + std::memcpy(sunDirB, susDataProcessed->susVecTot.value, 3 * sizeof(double)); } double exclAngle = acsParameters.strParameters.exclusionAngle, blindStart = acsParameters.targetModeControllerParameters.blindAvoidStart, blindEnd = acsParameters.targetModeControllerParameters.blindAvoidStop; - double sightAngleSun = VectorOperations::dot(acsParameters.strParameters.boresightAxis, sunDirB); @@ -190,8 +183,8 @@ void Guidance::targetQuatPtg(ACS::SensorValues *sensorValues, ACS::OutputValues } } -void Guidance::comparePtg(double targetQuat[4], ACS::OutputValues *outputValues, - double refSatRate[3], double quatError[3], double deltaRate[3]) { +void Guidance::comparePtg(double targetQuat[4], acsctrl::MekfData *mekfData, double refSatRate[3], + double quatErrorComplete[4], double quatError[3], double deltaRate[3]) { double quatRef[4] = {0, 0, 0, 0}; quatRef[0] = acsParameters.targetModeControllerParameters.quatRef[0]; quatRef[1] = acsParameters.targetModeControllerParameters.quatRef[1]; @@ -199,9 +192,7 @@ void Guidance::comparePtg(double targetQuat[4], ACS::OutputValues *outputValues, quatRef[3] = acsParameters.targetModeControllerParameters.quatRef[3]; double satRate[3] = {0, 0, 0}; - satRate[0] = outputValues->satRateMekf[0]; - satRate[1] = outputValues->satRateMekf[1]; - satRate[2] = outputValues->satRateMekf[2]; + std::memcpy(satRate, mekfData->satRotRateMekf.value, 3 * sizeof(double)); VectorOperations::subtract(satRate, refSatRate, deltaRate, 3); // valid checks ? double quatErrorMtx[4][4] = {{quatRef[3], quatRef[2], -quatRef[1], -quatRef[0]}, @@ -209,7 +200,6 @@ void Guidance::comparePtg(double targetQuat[4], ACS::OutputValues *outputValues, {quatRef[1], -quatRef[0], quatRef[3], -quatRef[2]}, {quatRef[0], -quatRef[1], quatRef[2], quatRef[3]}}; - double quatErrorComplete[4] = {0, 0, 0, 0}; MatrixOperations::multiply(*quatErrorMtx, targetQuat, quatErrorComplete, 4, 4, 1); if (quatErrorComplete[3] < 0) { @@ -225,8 +215,8 @@ void Guidance::comparePtg(double targetQuat[4], ACS::OutputValues *outputValues, } void Guidance::getDistributionMatrixRw(ACS::SensorValues *sensorValues, double *rwPseudoInv) { - if (sensorValues->rw1Set.isValid() && sensorValues->rw2Set.isValid() && sensorValues->rw3Set.isValid() && - sensorValues->rw4Set.isValid()) { + if (sensorValues->rw1Set.isValid() && sensorValues->rw2Set.isValid() && + sensorValues->rw3Set.isValid() && sensorValues->rw4Set.isValid()) { rwPseudoInv[0] = acsParameters.rwMatrices.pseudoInverse[0][0]; rwPseudoInv[1] = acsParameters.rwMatrices.pseudoInverse[0][1]; rwPseudoInv[2] = acsParameters.rwMatrices.pseudoInverse[0][2]; diff --git a/mission/controller/acs/Guidance.h b/mission/controller/acs/Guidance.h index bf53d767..4c699561 100644 --- a/mission/controller/acs/Guidance.h +++ b/mission/controller/acs/Guidance.h @@ -8,35 +8,37 @@ #ifndef GUIDANCE_H_ #define GUIDANCE_H_ - -#include "AcsParameters.h" -#include "SensorValues.h" -#include "OutputValues.h" #include +#include "../controllerdefinitions/AcsCtrlDefinitions.h" +#include "AcsParameters.h" +#include "SensorValues.h" class Guidance { -public: - Guidance(AcsParameters *acsParameters_); - virtual ~Guidance(); + public: + Guidance(AcsParameters *acsParameters_); + virtual ~Guidance(); - void getTargetParamsSafe(double sunTargetSafe[3], double satRateRef[3]); + void getTargetParamsSafe(double sunTargetSafe[3], double satRateRef[3]); - // Function to get the target quaternion and refence rotation rate from gps position and position of the ground station - void targetQuatPtg(ACS::SensorValues* sensorValues, ACS::OutputValues *outputValues, timeval now, - double targetQuat[4], double refSatRate[3]); + // Function to get the target quaternion and refence rotation rate from gps position and position + // of the ground station + void targetQuatPtg(ACS::SensorValues *sensorValues, acsctrl::MekfData *mekfData, + acsctrl::SusDataProcessed *susDataProcessed, timeval now, double targetQuat[4], + double refSatRate[3]); - // @note: compares target Quaternion and reference quaternion, also actual satellite rate and desired - void comparePtg( double targetQuat[4], ACS::OutputValues *outputValues, double refSatRate[3], double quatError[3], double deltaRate[3] ); + // @note: compares target Quaternion and reference quaternion, also actual satellite rate and + // desired + void comparePtg(double targetQuat[4], acsctrl::MekfData *mekfData, double refSatRate[3], + double quatErrorComplete[4], double quatError[3], double deltaRate[3]); -// @note: will give back the pseudoinverse matrix for the reaction wheel depending on the valid reation wheel -// maybe can be done in "commanding.h" - void getDistributionMatrixRw(ACS::SensorValues* sensorValues, double *rwPseudoInv); + // @note: will give back the pseudoinverse matrix for the reaction wheel depending on the valid + // reation wheel maybe can be done in "commanding.h" + void getDistributionMatrixRw(ACS::SensorValues *sensorValues, double *rwPseudoInv); - -private: - AcsParameters acsParameters; - bool strBlindAvoidFlag = false; + private: + AcsParameters acsParameters; + bool strBlindAvoidFlag = false; }; #endif /* ACS_GUIDANCE_H_ */ diff --git a/mission/controller/acs/Igrf13Model.cpp b/mission/controller/acs/Igrf13Model.cpp index 75d3c9a1..fcd95b68 100644 --- a/mission/controller/acs/Igrf13Model.cpp +++ b/mission/controller/acs/Igrf13Model.cpp @@ -6,120 +6,120 @@ */ #include "Igrf13Model.h" -#include "util/MathOperations.h" -#include -#include -#include -//#include + #include #include #include #include +#include +#include +#include +#include "util/MathOperations.h" -Igrf13Model::Igrf13Model(){ -} -Igrf13Model::~Igrf13Model(){ -} +Igrf13Model::Igrf13Model() {} +Igrf13Model::~Igrf13Model() {} void Igrf13Model::magFieldComp(const double longitude, const double gcLatitude, - const double altitude, timeval timeOfMagMeasurement, double* magFieldModelInertial) { + const double altitude, timeval timeOfMagMeasurement, + double* magFieldModelInertial) { + double phi = longitude, theta = gcLatitude; // geocentric + /* Here is the co-latitude needed*/ + theta -= 90 * Math::PI / 180; + theta *= (-1); - double phi = longitude, theta = gcLatitude; //geocentric - /* Here is the co-latitude needed*/ - theta -= 90*Math::PI/180; - theta *= (-1); + double rE = 6371200.0; // radius earth [m] + /* Predefine recursive associated Legendre polynomials */ + double P11 = 1; + double P10 = P11; // P10 = P(n-1,m-0) + double dP11 = 0; // derivative + double dP10 = dP11; // derivative - double rE = 6371200.0; // radius earth [m] - /* Predefine recursive associated Legendre polynomials */ - double P11 = 1; - double P10 = P11; //P10 = P(n-1,m-0) - double dP11 = 0; //derivative - double dP10 = dP11; //derivative + double P2 = 0, dP2 = 0, P20 = 0, dP20 = 0, K = 0; - double P2 = 0, dP2 = 0, P20 = 0, dP20 = 0, K = 0; + for (int m = 0; m <= igrfOrder; m++) { + for (int n = 1; n <= igrfOrder; n++) { + if (m <= n) { + /* Calculation of Legendre Polynoms (normalised) */ + if (n == m) { + P2 = sin(theta) * P11; + dP2 = sin(theta) * dP11 - cos(theta) * P11; + P11 = P2; + P10 = P11; + P20 = 0; + dP11 = dP2; + dP10 = dP11; + dP20 = 0; + } else if (n == 1) { + P2 = cos(theta) * P10; + dP2 = cos(theta) * dP10 - sin(theta) * P10; + P20 = P10; + P10 = P2; + dP20 = dP10; + dP10 = dP2; + } else { + K = (pow((n - 1), 2) - pow(m, 2)) / ((2 * n - 1) * (2 * n - 3)); + P2 = cos(theta) * P10 - K * P20; + dP2 = cos(theta) * dP10 - sin(theta) * P10 - K * dP20; + P20 = P10; + P10 = P2; + dP20 = dP10; + dP10 = dP2; + } + /* gradient of scalar potential towards radius */ + magFieldModel[0] += + pow(rE / (altitude + rE), (n + 2)) * (n + 1) * + ((updatedG[m][n - 1] * cos(m * phi) + updatedH[m][n - 1] * sin(m * phi)) * P2); + /* gradient of scalar potential towards phi */ + magFieldModel[1] += + pow(rE / (altitude + rE), (n + 2)) * + ((updatedG[m][n - 1] * cos(m * phi) + updatedH[m][n - 1] * sin(m * phi)) * dP2); + /* gradient of scalar potential towards theta */ + magFieldModel[2] += + pow(rE / (altitude + rE), (n + 2)) * + ((-updatedG[m][n - 1] * sin(m * phi) + updatedH[m][n - 1] * cos(m * phi)) * P2 * m); + } + } + } - for (int m = 0; m <= igrfOrder; m++) { - for (int n = 1; n <= igrfOrder; n++) { - if (m <= n) { - /* Calculation of Legendre Polynoms (normalised) */ - if (n == m) { - P2 = sin(theta) * P11; - dP2 = sin(theta) * dP11 - cos(theta) * P11; - P11 = P2; - P10 = P11; - P20 = 0; - dP11 = dP2; - dP10 = dP11; - dP20 = 0; - } else if (n == 1) { - P2 = cos(theta) * P10; - dP2 = cos(theta) * dP10 - sin(theta) * P10; - P20 = P10; - P10 = P2; - dP20 = dP10; - dP10 = dP2; - } else { - K = (pow((n - 1), 2) - pow(m, 2)) - / ((2 * n - 1) * (2 * n - 3)); - P2 = cos(theta) * P10 - K * P20; - dP2 = cos(theta) * dP10 - sin(theta) * P10 - K * dP20; - P20 = P10; - P10 = P2; - dP20 = dP10; - dP10 = dP2; - } - /* gradient of scalar potential towards radius */ - magFieldModel[0]+=pow(rE/(altitude+rE),(n+2))*(n+1)* - ((updatedG[m][n-1]*cos(m*phi) + updatedH[m][n-1]*sin(m*phi))*P2); - /* gradient of scalar potential towards phi */ - magFieldModel[1]+=pow(rE/(altitude+rE),(n+2))* - ((updatedG[m][n-1]*cos(m*phi) + updatedH[m][n-1]*sin(m*phi))*dP2); - /* gradient of scalar potential towards theta */ - magFieldModel[2]+=pow(rE/(altitude+rE),(n+2))* - ((-updatedG[m][n-1]*sin(m*phi) + updatedH[m][n-1]*cos(m*phi))*P2*m); - } - } - } + magFieldModel[1] *= -1; + magFieldModel[2] *= (-1 / sin(theta)); - magFieldModel[1] *= -1; - magFieldModel[2] *= (-1 / sin(theta)); + /* Next step: transform into inertial KOS (IJK)*/ + // Julean Centuries + double JD2000Floor = 0; + double JD2000 = MathOperations::convertUnixToJD2000(timeOfMagMeasurement); + JD2000Floor = floor(JD2000); + double JC2000 = JD2000Floor / 36525; - /* Next step: transform into inertial KOS (IJK)*/ - //Julean Centuries - double JD2000Floor = 0; - double JD2000 = MathOperations::convertUnixToJD2000(timeOfMagMeasurement); - JD2000Floor = floor(JD2000); - double JC2000 = JD2000Floor / 36525; + double gst = 100.4606184 + 36000.77005361 * JC2000 + 0.00038793 * pow(JC2000, 2) - + 0.000000026 * pow(JC2000, 3); // greenwich sidereal time + gst *= PI / 180; // convert to radians + double sec = + (JD2000 - JD2000Floor) * 86400; // Seconds on this day (Universal time) // FROM GPS ? + double omega0 = 0.00007292115; // mean angular velocity earth [rad/s] + gst += omega0 * sec; - double gst = 100.4606184 + 36000.77005361 * JC2000 + 0.00038793 * pow(JC2000,2) - - 0.000000026 * pow(JC2000,3); //greenwich sidereal time - gst *= PI/180; //convert to radians - double sec = (JD2000 - JD2000Floor) * 86400; // Seconds on this day (Universal time) // FROM GPS ? - double omega0 = 0.00007292115; // mean angular velocity earth [rad/s] - gst +=omega0 * sec; + double lst = gst + longitude; // local sidereal time [rad] - double lst = gst + longitude; //local sidereal time [rad] + magFieldModelInertial[0] = magFieldModel[0] * cos(theta) + + magFieldModel[1] * sin(theta) * cos(lst) - magFieldModel[1] * sin(lst); + magFieldModelInertial[1] = magFieldModel[0] * cos(theta) + + magFieldModel[1] * sin(theta) * sin(lst) + magFieldModel[1] * cos(lst); + magFieldModelInertial[2] = magFieldModel[0] * sin(theta) + magFieldModel[1] * cos(lst); - - - magFieldModelInertial[0] = magFieldModel[0] * cos(theta) + magFieldModel[1] * sin(theta)*cos(lst) - magFieldModel[1] * sin(lst); - magFieldModelInertial[1] = magFieldModel[0] * cos(theta) + magFieldModel[1] * sin(theta)*sin(lst) + magFieldModel[1] * cos(lst); - magFieldModelInertial[2] = magFieldModel[0] * sin(theta) + magFieldModel[1] * cos(lst); - - double normVecMagFieldInert[3] = {0,0,0}; - VectorOperations::normalize(magFieldModelInertial, normVecMagFieldInert, 3); + double normVecMagFieldInert[3] = {0, 0, 0}; + VectorOperations::normalize(magFieldModelInertial, normVecMagFieldInert, 3); } -void Igrf13Model::updateCoeffGH(timeval timeOfMagMeasurement){ - - double JD2000Igrf = (2458850.0-2451545); //Begin of IGRF-13 (2020-01-01,00:00:00) in JD2000 - double JD2000 = MathOperations::convertUnixToJD2000(timeOfMagMeasurement); - double days = ceil(JD2000-JD2000Igrf); - for(int i = 0;i <= igrfOrder; i++){ - for(int j = 0;j <= (igrfOrder-1); j++){ - updatedG[i][j] = coeffG[i][j] + svG[i][j] * (days/365); - updatedH[i][j] = coeffH[i][j] + svH[i][j] * (days/365); - } - } +void Igrf13Model::updateCoeffGH(timeval timeOfMagMeasurement) { + double JD2000Igrf = (2458850.0 - 2451545); // Begin of IGRF-13 (2020-01-01,00:00:00) in JD2000 + double JD2000 = MathOperations::convertUnixToJD2000(timeOfMagMeasurement); + double days = ceil(JD2000 - JD2000Igrf); + for (int i = 0; i <= igrfOrder; i++) { + for (int j = 0; j <= (igrfOrder - 1); j++) { + updatedG[i][j] = coeffG[i][j] + svG[i][j] * (days / 365); + updatedH[i][j] = coeffH[i][j] + svH[i][j] * (days / 365); + } + } } diff --git a/mission/controller/acs/Igrf13Model.h b/mission/controller/acs/Igrf13Model.h index d89865ca..aa7e8b73 100644 --- a/mission/controller/acs/Igrf13Model.h +++ b/mission/controller/acs/Igrf13Model.h @@ -16,103 +16,107 @@ #ifndef IGRF13MODEL_H_ #define IGRF13MODEL_H_ -#include +#include #include #include #include -#include +#include // Output should be transformed to [T] instead of [nT] // Updating Coefficients has to be implemented yet. Question, updating everyday ? -class Igrf13Model/*:public HasParametersIF*/{ +class Igrf13Model /*:public HasParametersIF*/ { + public: + Igrf13Model(); + virtual ~Igrf13Model(); -public: - Igrf13Model(); - virtual ~Igrf13Model(); + // Main Function + void magFieldComp(const double longitude, const double gcLatitude, const double altitude, + timeval timeOfMagMeasurement, double* magFieldModelInertial); + // Right now the radius for igrf is simply with r0 + altitude calculated. In reality the radius is + // oriented from the satellite to earth COM Difference up to 25 km, which is 5 % of the total + // flight altitude + /* Inputs: + * - longitude: geocentric longitude [rad] + * - latitude: geocentric latitude [rad] + * - altitude: [m] + * - timeOfMagMeasurement: time of actual measurement [s] + * + * Outputs: + * - magFieldModelInertial: Magnetic Field Vector in IJK KOS [nT]*/ - // Main Function - void magFieldComp(const double longitude, const double gcLatitude, const double altitude, timeval timeOfMagMeasurement,double* magFieldModelInertial); - // Right now the radius for igrf is simply with r0 + altitude calculated. In reality the radius is oriented from the satellite to earth COM - // Difference up to 25 km, which is 5 % of the total flight altitude - /* Inputs: - * - longitude: geocentric longitude [rad] - * - latitude: geocentric latitude [rad] - * - altitude: [m] - * - timeOfMagMeasurement: time of actual measurement [s] - * - * Outputs: - * - magFieldModelInertial: Magnetic Field Vector in IJK KOS [nT]*/ + // Coefficient wary over year, could be updated sometimes. + void updateCoeffGH(timeval timeOfMagMeasurement); // Secular variation (SV) + double magFieldModel[3]; + private: + const double coeffG[14][13] = { + {-29404.8, -2499.6, 1363.2, 903.0, -234.3, 66.0, 80.6, 23.7, 5.0, -1.9, 3.0, -2.0, 0.1}, + {-1450.9, 2982.0, -2381.2, 809.5, 363.2, 65.5, -76.7, 9.7, 8.4, -6.2, -1.4, -0.1, -0.9}, + {0.0, 1677.0, 1236.2, 86.3, 187.8, 72.9, -8.2, -17.6, 2.9, -0.1, -2.5, 0.5, 0.5}, + {0.0, 0.0, 525.7, -309.4, -140.7, -121.5, 56.5, -0.5, -1.5, 1.7, 2.3, 1.3, 0.7}, + {0.0, 0.0, 0.0, 48.0, -151.2, -36.2, 15.8, -21.1, -1.1, -0.9, -0.9, -1.2, -0.3}, + {0.0, 0.0, 0.0, 0.0, 13.5, 13.5, 6.4, 15.3, -13.2, 0.7, 0.3, 0.7, 0.8}, + {0.0, 0.0, 0.0, 0.0, 0.0, -64.7, -7.2, 13.7, 1.1, -0.9, -0.7, 0.3, 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.8, -16.5, 8.8, 1.9, -0.1, 0.5, 0.8}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3, -9.3, 1.4, 1.4, -0.3, 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -11.9, -2.4, -0.6, -0.5, 0.4}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8, 0.2, 0.1, 0.1}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.1, -1.1, 0.5}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3, -0.5}, + {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.4}}; // [m][n] in nT - // Coefficient wary over year, could be updated sometimes. - void updateCoeffGH(timeval timeOfMagMeasurement); //Secular variation (SV) - double magFieldModel[3]; + const double coeffH[14][13] = { + {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}, + {4652.5, -2991.6, -82.1, 281.9, 47.7, -19.1, -51.5, 8.4, -23.4, 3.4, 0.0, -1.2, -0.9}, + {0.0, -734.6, 241.9, -158.4, 208.3, 25.1, -16.9, -15.3, 11.0, -0.2, 2.5, 0.5, 0.6}, + {0.0, 0.0, -543.4, 199.7, -121.2, 52.8, 2.2, 12.8, 9.8, 3.6, -0.6, 1.4, 1.4}, + {0.0, 0.0, 0.0, -349.7, 32.3, -64.5, 23.5, -11.7, -5.1, 4.8, -0.4, -1.8, -0.4}, + {0.0, 0.0, 0.0, 0.0, 98.9, 8.9, -2.2, 14.9, -6.3, -8.6, 0.6, 0.1, -1.3}, + {0.0, 0.0, 0.0, 0.0, 0.0, 68.1, -27.2, 3.6, 7.8, -0.1, -0.2, 0.8, -0.1}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8, -6.9, 0.4, -4.3, -1.7, -0.2, 0.3}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8, -1.4, -3.4, -1.6, 0.6, -0.1}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.6, -0.1, -3.0, 0.2, 0.5}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.8, -2.0, -0.9, 0.5}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.6, 0.0, -0.4}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5, -0.4}, + {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.6}}; // [m][n] in nT -private: - const double coeffG[14][13] = {{-29404.8,-2499.6, 1363.2, 903.0,-234.3, 66.0, 80.6, 23.7, 5.0,-1.9, 3.0,-2.0, 0.1}, - { -1450.9, 2982.0,-2381.2, 809.5, 363.2, 65.5,-76.7, 9.7, 8.4,-6.2,-1.4,-0.1,-0.9}, - { 0.0, 1677.0, 1236.2, 86.3, 187.8, 72.9, -8.2,-17.6, 2.9,-0.1,-2.5, 0.5, 0.5}, - { 0.0, 0.0, 525.7,-309.4,-140.7,-121.5, 56.5, -0.5, -1.5, 1.7, 2.3, 1.3, 0.7}, - { 0.0, 0.0, 0.0, 48.0,-151.2, -36.2, 15.8,-21.1, -1.1,-0.9,-0.9,-1.2,-0.3}, - { 0.0, 0.0, 0.0, 0.0, 13.5, 13.5, 6.4, 15.3,-13.2, 0.7, 0.3, 0.7, 0.8}, - { 0.0, 0.0, 0.0, 0.0, 0.0, -64.7, -7.2, 13.7, 1.1,-0.9,-0.7, 0.3, 0.0}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.8,-16.5, 8.8, 1.9,-0.1, 0.5, 0.8}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3, -9.3, 1.4, 1.4,-0.3, 0.0}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,-11.9,-2.4,-0.6,-0.5, 0.4}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,-3.8, 0.2, 0.1, 0.1}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.1,-1.1, 0.5}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,-0.3,-0.5}, - { 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.4}}; // [m][n] in nT + const double svG[14][13] = { + {5.7, -11.0, 2.2, -1.2, -0.3, -0.5, -0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}, + {7.4, -7.0, -5.9, -1.6, 0.5, -0.3, -0.2, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, -2.1, 3.1, -5.9, -0.6, 0.4, 0.0, -0.1, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, -12.0, 5.2, 0.2, 1.3, 0.7, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, -5.1, 1.3, -1.4, 0.1, -0.1, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.9, 0.0, -0.5, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.9, -0.8, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.8, -0.1, 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.4, 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}, + {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, 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, 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}}; // [m][n] in nT - const double coeffH[14][13] = {{ 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 }, - {4652.5,-2991.6, -82.1, 281.9, 47.7,-19.1,-51.5, 8.4,-23.4, 3.4, 0.0,-1.2,-0.9}, - { 0.0, -734.6, 241.9,-158.4, 208.3, 25.1,-16.9,-15.3, 11.0,-0.2, 2.5, 0.5, 0.6}, - { 0.0, 0.0,-543.4, 199.7,-121.2, 52.8, 2.2, 12.8, 9.8, 3.6,-0.6, 1.4, 1.4}, - { 0.0, 0.0, 0.0,-349.7, 32.3,-64.5, 23.5,-11.7, -5.1, 4.8,-0.4,-1.8,-0.4}, - { 0.0, 0.0, 0.0, 0.0, 98.9, 8.9, -2.2, 14.9, -6.3,-8.6, 0.6, 0.1,-1.3}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 68.1,-27.2, 3.6, 7.8,-0.1,-0.2, 0.8,-0.1}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8, -6.9, 0.4,-4.3,-1.7,-0.2, 0.3}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8, -1.4,-3.4,-1.6, 0.6,-0.1}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.6,-0.1,-3.0, 0.2, 0.5}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,-8.8,-2.0,-0.9, 0.5}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,-2.6, 0.0,-0.4}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5,-0.4}, - { 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.6}}; // [m][n] in nT + const double svH[14][13] = { + {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}, + {-25.9, -30.2, 6.0, -0.1, 0.0, 0.0, 0.6, -0.2, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, -22.4, -1.1, 6.5, 2.5, -1.6, 0.6, 0.6, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.5, 3.6, -0.6, -1.3, -0.8, -0.2, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, -5.0, 3.0, 0.8, -0.2, 0.5, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.3, 0.0, -1.1, -0.3, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.1, -0.4, 0.0, 0.0, 0.0, 0.0, 0.0}, + {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.5, 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}, + {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, 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, 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, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}}; // [m][n] in nT - const double svG[14][13] = {{5.7,-11.0, 2.2,-1.2,-0.3,-0.5,-0.1, 0.0, 0.0, 0.0, 0.0, 0.0 ,0.0}, - {7.4, -7.0, -5.9,-1.6, 0.5,-0.3,-0.2, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0}, - {0.0, -2.1, 3.1,-5.9,-0.6, 0.4, 0.0,-0.1, 0.0, 0.0, 0.0, 0.0, 0.0}, - {0.0, 0.0,-12.0, 5.2, 0.2, 1.3, 0.7, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0}, - {0.0, 0.0, 0.0,-5.1, 1.3,-1.4, 0.1,-0.1, 0.0, 0.0, 0.0, 0.0, 0.0}, - {0.0, 0.0, 0.0, 0.0, 0.9, 0.0,-0.5, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0}, - {0.0, 0.0, 0.0, 0.0, 0.0, 0.9,-0.8, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0}, - {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.8,-0.1, 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.4, 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}, - {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, 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, 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}}; // [m][n] in nT - - const double svH[14][13] = {{ 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}, - {-25.9,-30.2, 6.0,-0.1, 0.0, 0.0, 0.6,-0.2, 0.0, 0.0, 0.0, 0.0, 0.0}, - { 0.0,-22.4,-1.1, 6.5, 2.5,-1.6, 0.6, 0.6, 0.0, 0.0, 0.0, 0.0, 0.0}, - { 0.0, 0.0, 0.5, 3.6,-0.6,-1.3,-0.8,-0.2, 0.0, 0.0, 0.0, 0.0, 0.0}, - { 0.0, 0.0, 0.0,-5.0, 3.0, 0.8,-0.2, 0.5, 0.0, 0.0, 0.0, 0.0, 0.0}, - { 0.0, 0.0, 0.0, 0.0, 0.3, 0.0,-1.1,-0.3, 0.0, 0.0, 0.0, 0.0, 0.0}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.1,-0.4, 0.0, 0.0, 0.0, 0.0, 0.0}, - { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.5, 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}, - { 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, 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, 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, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}}; // [m][n] in nT - - double updatedG[14][13]; - double updatedH[14][13]; - static const int igrfOrder = 13; // degree of truncation + double updatedG[14][13]; + double updatedH[14][13]; + static const int igrfOrder = 13; // degree of truncation }; #endif /* IGRF13MODEL_H_ */ diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.cpp b/mission/controller/acs/MultiplicativeKalmanFilter.cpp index 8cfa0ad3..cc136f61 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.cpp +++ b/mission/controller/acs/MultiplicativeKalmanFilter.cpp @@ -7,6 +7,7 @@ #include "MultiplicativeKalmanFilter.h" +#include #include #include #include @@ -34,11 +35,11 @@ void MultiplicativeKalmanFilter::loadAcsParameters(AcsParameters *acsParameters_ void MultiplicativeKalmanFilter::reset() {} void 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) { // valids for "model measurements"? + const double *magneticField_, const bool validMagField_, const double *sunDir_, + const bool validSS, const double *sunDirJ, const bool validSSModel, const double *magFieldJ, + const bool validMagModel) { // valids for "model measurements"? // check for valid mag/sun - if (*validMagField_ && *validSS && *validSSModel && *validMagModel) { + if (validMagField_ && validSS && validSSModel && validMagModel) { validInit = true; // AcsParameters mekfEstParams; // loadAcsParameters(&mekfEstParams); @@ -208,48 +209,78 @@ void MultiplicativeKalmanFilter::init( // --------------- 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 *outputQuat, double *outputSatRate) { + 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) { // Check for GYR Measurements // AcsParameters mekfEstParams; // loadAcsParameters(&mekfEstParams); int MDF = 0; // Matrix Dimension Factor - if (!(*validGYRs_)) { + if (!validGYRs_) { + { + PoolReadGuard pg(mekfData); + if (pg.getReadResult() == returnvalue::OK) { + double unitQuat[4] = {0.0, 0.0, 0.0, 1.0}; + double zeroVec[3] = {0.0, 0.0, 0.0}; + std::memcpy(mekfData->quatMekf.value, unitQuat, 4 * sizeof(double)); + std::memcpy(mekfData->satRotRateMekf.value, zeroVec, 3 * sizeof(double)); + mekfData->setValidity(false, true); + } + } validMekf = false; return KALMAN_NO_GYR_MEAS; } // Check for Model Calculations - else if (!(*validSSModel) || !(*validMagModel)) { + else if (!validSSModel || !validMagModel) { + { + PoolReadGuard pg(mekfData); + if (pg.getReadResult() == returnvalue::OK) { + double unitQuat[4] = {0.0, 0.0, 0.0, 1.0}; + double zeroVec[3] = {0.0, 0.0, 0.0}; + std::memcpy(mekfData->quatMekf.value, unitQuat, 4 * sizeof(double)); + std::memcpy(mekfData->satRotRateMekf.value, zeroVec, 3 * sizeof(double)); + mekfData->setValidity(false, true); + } + } validMekf = false; return KALMAN_NO_MODEL; } // Check Measurements available from SS, MAG, STR - if (*validSS && *validMagField_ && *validSTR_) { + if (validSS && validMagField_ && validSTR_) { sensorsAvail = 1; MDF = 9; - } else if (*validSS && *validMagField_ && !(*validSTR_)) { + } else if (validSS && validMagField_ && !validSTR_) { sensorsAvail = 2; MDF = 6; - } else if (*validSS && !(*validMagField_) && *validSTR_) { + } else if (validSS && !validMagField_ && validSTR_) { sensorsAvail = 3; MDF = 6; - } else if (!(*validSS) && *validMagField_ && *validSTR_) { + } else if (!validSS && validMagField_ && validSTR_) { sensorsAvail = 4; MDF = 6; - } else if (*validSS && !(*validMagField_) && !(*validSTR_)) { + } else if (validSS && !validMagField_ && !(validSTR_)) { sensorsAvail = 5; MDF = 3; - } else if (!(*validSS) && *validMagField_ && !(*validSTR_)) { + } else if (!validSS && validMagField_ && !validSTR_) { sensorsAvail = 6; MDF = 3; - } else if (!(*validSS) && !(*validMagField_) && *validSTR_) { + } else if (!validSS && !validMagField_ && validSTR_) { sensorsAvail = 7; MDF = 3; } else { sensorsAvail = 8; // no measurements validMekf = false; + { + PoolReadGuard pg(mekfData); + if (pg.getReadResult() == returnvalue::OK) { + double unitQuat[4] = {0.0, 0.0, 0.0, 1.0}; + double zeroVec[3] = {0.0, 0.0, 0.0}; + std::memcpy(mekfData->quatMekf.value, unitQuat, 4 * sizeof(double)); + std::memcpy(mekfData->satRotRateMekf.value, zeroVec, 3 * sizeof(double)); + mekfData->setValidity(false, true); + } + } return returnvalue::FAILED; } @@ -289,7 +320,7 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst( MathOperations::skewMatrix(magEstB, *measSensMatrix22); double measVecQuat[3] = {0, 0, 0}; - if (*validSTR_) { + if (validSTR_) { double quatError[4] = {0, 0, 0, 0}; double invPropagatedQuat[4] = {0, 0, 0, 0}; QuaternionOperations::inverse(propagatedQuaternion, invPropagatedQuat); @@ -913,11 +944,6 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst( VectorOperations::add(propagatedQuaternion, errQuatTerm, quatBJ, 4); VectorOperations::normalize(quatBJ, quatBJ, 4); - outputQuat[0] = quatBJ[0]; - outputQuat[1] = quatBJ[1]; - outputQuat[2] = quatBJ[2]; - outputQuat[3] = quatBJ[3]; - double updatedGyroBias[3] = {0, 0, 0}; VectorOperations::add(biasGYR, errStateGyroBias, updatedGyroBias, 3); // Bias GYR State @@ -940,11 +966,6 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst( {rotRateEst[2], 0, -rotRateEst[0]}, {-rotRateEst[1], rotRateEst[0], 0}}; - // Corrected Sat Rate via Bias - outputSatRate[0] = rotRateEst[0]; - outputSatRate[1] = rotRateEst[1]; - outputSatRate[2] = rotRateEst[2]; - // Discrete Process Noise Covariance Q double discProcessNoiseCov[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}}; @@ -1144,5 +1165,14 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst( // Check for new data in measurement -> SensorProcessing ? + { + PoolReadGuard pg(mekfData); + if (pg.getReadResult() == returnvalue::OK) { + std::memcpy(mekfData->quatMekf.value, quatBJ, 4 * sizeof(double)); + std::memcpy(mekfData->satRotRateMekf.value, rotRateEst, 3 * sizeof(double)); + mekfData->setValidity(true, true); + } + } + return returnvalue::OK; } diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.h b/mission/controller/acs/MultiplicativeKalmanFilter.h index f1d2d7a0..5eb47418 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.h +++ b/mission/controller/acs/MultiplicativeKalmanFilter.h @@ -18,10 +18,9 @@ #include //uint8_t #include /*purpose, timeval ?*/ -#include "config/classIds.h" -//#include <_timeval.h> - +#include "../controllerdefinitions/AcsCtrlDefinitions.h" #include "AcsParameters.h" +#include "config/classIds.h" class MultiplicativeKalmanFilter { public: @@ -40,9 +39,9 @@ class MultiplicativeKalmanFilter { * sunDirJ sun direction vector in the ECI frame * magFieldJ magnetic field vector in the ECI frame */ - void 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); + void 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); /* @brief: mekfEst() - This function calculates the quaternion and gyro bias of the Kalman Filter * for the current step after the initalization @@ -58,11 +57,11 @@ class MultiplicativeKalmanFilter { * calculations, KALMAN_INVERSION_FAILED if the calculation of the Gain matrix was not possible, * RETURN_OK else */ - ReturnValue_t 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 *outputQuat, double *outputSatRate); + ReturnValue_t 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); // Declaration of Events (like init) and memberships // static const uint8_t INTERFACE_ID = CLASS_ID::MEKF; //CLASS IDS ND diff --git a/mission/controller/acs/Navigation.cpp b/mission/controller/acs/Navigation.cpp index 2c1596e5..921ae604 100644 --- a/mission/controller/acs/Navigation.cpp +++ b/mission/controller/acs/Navigation.cpp @@ -21,28 +21,34 @@ Navigation::Navigation(AcsParameters *acsParameters_) : multiplicativeKalmanFilt Navigation::~Navigation() {} -void Navigation::useMekf(ACS::SensorValues *sensorValues, ACS::OutputValues *outputValues, +void Navigation::useMekf(ACS::SensorValues *sensorValues, + acsctrl::GyrDataProcessed *gyrDataProcessed, + acsctrl::MgmDataProcessed *mgmDataProcessed, + acsctrl::SusDataProcessed *susDataProcessed, acsctrl::MekfData *mekfData, ReturnValue_t *mekfValid) { double quatJB[4] = {sensorValues->strSet.caliQx.value, sensorValues->strSet.caliQy.value, sensorValues->strSet.caliQz.value, sensorValues->strSet.caliQw.value}; - bool quatJBValid = - (sensorValues->strSet.caliQx.isValid() && sensorValues->strSet.caliQy.isValid() && - sensorValues->strSet.caliQz.isValid() && sensorValues->strSet.caliQw.isValid()); + bool quatJBValid = sensorValues->strSet.caliQx.isValid() && + sensorValues->strSet.caliQy.isValid() && + sensorValues->strSet.caliQz.isValid() && sensorValues->strSet.caliQw.isValid(); if (kalmanInit) { *mekfValid = multiplicativeKalmanFilter.mekfEst( - quatJB, &quatJBValid, outputValues->satRateEst, &outputValues->satRateEstValid, - outputValues->magFieldEst, &outputValues->magFieldEstValid, outputValues->sunDirEst, - &outputValues->sunDirEstValid, outputValues->sunDirModel, &outputValues->sunDirModelValid, - outputValues->magFieldModel, &outputValues->magFieldModelValid, outputValues->quatMekfBJ, - outputValues->satRateMekf); // VALIDS FOR QUAT AND RATE ?? + quatJB, quatJBValid, gyrDataProcessed->gyrVecTot.value, + gyrDataProcessed->gyrVecTot.isValid(), 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); // VALIDS FOR QUAT AND RATE ?? } else { - multiplicativeKalmanFilter.init(outputValues->magFieldEst, &outputValues->magFieldEstValid, - outputValues->sunDirEst, &outputValues->sunDirEstValid, - outputValues->sunDirModel, &outputValues->sunDirModelValid, - outputValues->magFieldModel, &outputValues->magFieldModelValid); + multiplicativeKalmanFilter.init( + mgmDataProcessed->mgmVecTot.value, mgmDataProcessed->mgmVecTot.isValid(), + susDataProcessed->susVecTot.value, susDataProcessed->susVecTot.isValid(), + susDataProcessed->sunIjkModel.value, susDataProcessed->sunIjkModel.isValid(), + mgmDataProcessed->magIgrfModel.value, mgmDataProcessed->magIgrfModel.isValid()); kalmanInit = true; - *mekfValid = 0; + *mekfValid = returnvalue::OK; // Maybe we need feedback from kalmanfilter to identify if there was a problem with the // init of kalman filter where does this class know from that kalman filter was not diff --git a/mission/controller/acs/Navigation.h b/mission/controller/acs/Navigation.h index 6691b8aa..2474cb67 100644 --- a/mission/controller/acs/Navigation.h +++ b/mission/controller/acs/Navigation.h @@ -8,28 +8,28 @@ #ifndef NAVIGATION_H_ #define NAVIGATION_H_ - +#include "../controllerdefinitions/AcsCtrlDefinitions.h" #include "AcsParameters.h" -#include "SensorProcessing.h" #include "MultiplicativeKalmanFilter.h" +#include "SensorProcessing.h" #include "SensorValues.h" -#include "OutputValues.h" -class Navigation{ -public: - Navigation(AcsParameters *acsParameters_); //Input mode ? - virtual ~Navigation(); +class Navigation { + public: + Navigation(AcsParameters *acsParameters_); // Input mode ? + virtual ~Navigation(); - void useMekf(ACS::SensorValues* sensorValues, ACS::OutputValues *outputValues, ReturnValue_t *mekfValid); - void processSensorData(); + void useMekf(ACS::SensorValues *sensorValues, acsctrl::GyrDataProcessed *gyrDataProcessed, + acsctrl::MgmDataProcessed *mgmDataProcessed, + acsctrl::SusDataProcessed *susDataProcessed, acsctrl::MekfData *mekfData, + ReturnValue_t *mekfValid); + void processSensorData(); -protected: - -private: - MultiplicativeKalmanFilter multiplicativeKalmanFilter; - AcsParameters acsParameters; - bool kalmanInit = false; + protected: + private: + MultiplicativeKalmanFilter multiplicativeKalmanFilter; + AcsParameters acsParameters; + bool kalmanInit = false; }; #endif /* ACS_NAVIGATION_H_ */ - diff --git a/mission/controller/acs/OutputValues.cpp b/mission/controller/acs/OutputValues.cpp deleted file mode 100644 index 42730fb3..00000000 --- a/mission/controller/acs/OutputValues.cpp +++ /dev/null @@ -1,9 +0,0 @@ -#include "OutputValues.h" - -namespace ACS { - -OutputValues::OutputValues() {} - -OutputValues::~OutputValues() {} - -} // namespace ACS diff --git a/mission/controller/acs/OutputValues.h b/mission/controller/acs/OutputValues.h deleted file mode 100644 index bb1ed007..00000000 --- a/mission/controller/acs/OutputValues.h +++ /dev/null @@ -1,44 +0,0 @@ -#include - -#include "../controllerdefinitions/AcsCtrlDefinitions.h" - -#ifndef OUTPUTVALUES_H_ -#define OUTPUTVALUES_H_ - -namespace ACS { - -class OutputValues { - public: - OutputValues(); - virtual ~OutputValues(); - - double magFieldEst[3]; // sensor fusion (G) // output value - bool magFieldEstValid; - double magFieldModel[3]; // igrf (IJK) // - bool magFieldModelValid; - double magneticFieldVectorDerivative[3]; - bool magneticFieldVectorDerivativeValid; - - bool mgmUpdated; // ToDo: relic from FLP. most likely not used - - double sunDirEst[3]; // sensor fusion (G) - bool sunDirEstValid; - double sunDirModel[3]; // sun model (IJK) - bool sunDirModelValid; - - double quatMekfBJ[4]; // mekf - bool quatMekfBJValid; - - double satRateEst[3]; - bool satRateEstValid; - double satRateMekf[3]; // after mekf with correction of bias - bool satRateMekfValid; - double sunVectorDerivative[3]; - bool sunVectorDerivativeValid; - - double gcLatitude; // geocentric latitude, radian - double gdLongitude; // Radian longitude -}; -} // namespace ACS - -#endif /*OUTPUTVALUES_H_*/ diff --git a/mission/controller/acs/SensorProcessing.h b/mission/controller/acs/SensorProcessing.h index 11d2ebeb..61bd7a96 100644 --- a/mission/controller/acs/SensorProcessing.h +++ b/mission/controller/acs/SensorProcessing.h @@ -11,7 +11,6 @@ #include "../controllerdefinitions/AcsCtrlDefinitions.h" #include "AcsParameters.h" -#include "OutputValues.h" #include "SensorValues.h" #include "SusConverter.h" #include "config/classIds.h" diff --git a/mission/controller/acs/SensorValues.cpp b/mission/controller/acs/SensorValues.cpp index 152f866c..18f0d16f 100644 --- a/mission/controller/acs/SensorValues.cpp +++ b/mission/controller/acs/SensorValues.cpp @@ -90,4 +90,3 @@ ReturnValue_t SensorValues::update() { } } // namespace ACS - diff --git a/mission/controller/acs/control/Detumble.cpp b/mission/controller/acs/control/Detumble.cpp index 67903c7c..7421226d 100644 --- a/mission/controller/acs/control/Detumble.cpp +++ b/mission/controller/acs/control/Detumble.cpp @@ -32,34 +32,27 @@ void Detumble::loadAcsParameters(AcsParameters *acsParameters_){ } - -ReturnValue_t Detumble::bDotLaw(const double *magRate, const bool *magRateValid, - const double *magField, const bool *magFieldValid, - double *magMom) { - - if (!magRateValid || !magFieldValid) { - return DETUMBLE_NO_SENSORDATA; - } - double gain = detumbleCtrlParameters->gainD; - double factor = -gain / pow(VectorOperations::norm(magField,3),2); - VectorOperations::mulScalar(magRate, factor, magMom, 3); - return returnvalue::OK; - +ReturnValue_t Detumble::bDotLaw(const double *magRate, const bool magRateValid, + const double *magField, const bool magFieldValid, double *magMom) { + if (!magRateValid || !magFieldValid) { + return DETUMBLE_NO_SENSORDATA; + } + double gain = detumbleCtrlParameters->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) { + if (!magRateValid) { + return DETUMBLE_NO_SENSORDATA; + } - if (!magRateValid) { - return DETUMBLE_NO_SENSORDATA; - } - - double dipolMax = magnetorquesParameter->DipolMax; - for (int i = 0; i<3; i++) { - - magMom[i] = - dipolMax * sign(magRate[i]); - - } - - return returnvalue::OK; + double dipolMax = magnetorquesParameter->DipolMax; + for (int i = 0; i < 3; i++) { + magMom[i] = -dipolMax * sign(magRate[i]); + } + return returnvalue::OK; } diff --git a/mission/controller/acs/control/Detumble.h b/mission/controller/acs/control/Detumble.h index b85aaf86..375f67aa 100644 --- a/mission/controller/acs/control/Detumble.h +++ b/mission/controller/acs/control/Detumble.h @@ -9,7 +9,6 @@ #define ACS_CONTROL_DETUMBLE_H_ #include "../SensorValues.h" -#include "../OutputValues.h" #include "../AcsParameters.h" #include "../config/classIds.h" #include @@ -32,13 +31,12 @@ public: */ void loadAcsParameters(AcsParameters *acsParameters_); - ReturnValue_t bDotLaw(const double *magRate, const bool *magRateValid, - const double *magField, const bool *magFieldValid, - double *magMom); + ReturnValue_t bDotLaw(const double *magRate, const bool magRateValid, + const double *magField, const bool magFieldValid, double *magMom); - ReturnValue_t bangbangLaw(const double *magRate, const bool *magRateValid, double *magMom); + ReturnValue_t bangbangLaw(const double *magRate, const bool magRateValid, double *magMom); -private: + private: AcsParameters::DetumbleCtrlParameters* detumbleCtrlParameters; AcsParameters::MagnetorquesParameter* magnetorquesParameter; }; diff --git a/mission/controller/acs/control/PtgCtrl.cpp b/mission/controller/acs/control/PtgCtrl.cpp index 7160fb47..e06b576f 100644 --- a/mission/controller/acs/control/PtgCtrl.cpp +++ b/mission/controller/acs/control/PtgCtrl.cpp @@ -112,7 +112,7 @@ void PtgCtrl::ptgGroundstation(const double mode, const double *qError, const do } -void PtgCtrl::ptgDesaturation(double *magFieldEst, bool *magFieldEstValid, double *satRate, +void PtgCtrl::ptgDesaturation(double *magFieldEst, bool magFieldEstValid, double *satRate, int32_t *speedRw0, int32_t *speedRw1, int32_t *speedRw2, int32_t *speedRw3, double *mgtDpDes) { if (!(magFieldEstValid) || !(pointingModeControllerParameters->desatOn)) { diff --git a/mission/controller/acs/control/PtgCtrl.h b/mission/controller/acs/control/PtgCtrl.h index be67187d..64b4110c 100644 --- a/mission/controller/acs/control/PtgCtrl.h +++ b/mission/controller/acs/control/PtgCtrl.h @@ -19,7 +19,6 @@ #include #include "../AcsParameters.h" -#include "../OutputValues.h" #include "../SensorValues.h" #include "../config/classIds.h" @@ -45,7 +44,7 @@ class PtgCtrl { void ptgGroundstation(const double mode, const double *qError, const double *deltaRate, const double *rwPseudoInv, double *torqueRws); - void ptgDesaturation(double *magFieldEst, bool *magFieldEstValid, double *satRate, + void ptgDesaturation(double *magFieldEst, bool magFieldEstValid, double *satRate, int32_t *speedRw0, int32_t *speedRw1, int32_t *speedRw2, int32_t *speedRw3, double *mgtDpDes); diff --git a/mission/controller/acs/control/SafeCtrl.cpp b/mission/controller/acs/control/SafeCtrl.cpp index c892fc05..54ae27ee 100644 --- a/mission/controller/acs/control/SafeCtrl.cpp +++ b/mission/controller/acs/control/SafeCtrl.cpp @@ -28,12 +28,12 @@ void SafeCtrl::loadAcsParameters(AcsParameters *acsParameters_) { inertiaEIVE = &(acsParameters_->inertiaEIVE); } -ReturnValue_t SafeCtrl::safeMekf(timeval now, double *quatBJ, bool *quatBJValid, - double *magFieldModel, bool *magFieldModelValid, - double *sunDirModel, bool *sunDirModelValid, double *satRateMekf, - bool *rateMekfValid, double *sunDirRef, double *satRatRef, - double *outputMagMomB, bool *outputValid) { - if (!(*quatBJValid) || !(*magFieldModelValid) || !(*sunDirModelValid) || !(*rateMekfValid)) { +ReturnValue_t SafeCtrl::safeMekf(timeval now, double *quatBJ, bool quatBJValid, + double *magFieldModel, bool magFieldModelValid, + double *sunDirModel, bool sunDirModelValid, double *satRateMekf, + bool rateMekfValid, double *sunDirRef, double *satRatRef, + double *outputAngle, double *outputMagMomB, bool *outputValid) { + if (!quatBJValid || !magFieldModelValid || !sunDirModelValid || !rateMekfValid) { *outputValid = false; return SAFECTRL_MEKF_INPUT_INVALID; } @@ -80,31 +80,34 @@ ReturnValue_t SafeCtrl::safeMekf(timeval now, double *quatBJ, bool *quatBJValid, VectorOperations::cross(magFieldB, torqueCmd, torqueMgt); double normMag = VectorOperations::norm(magFieldB, 3); VectorOperations::mulScalar(torqueMgt, 1 / pow(normMag, 2), outputMagMomB, 3); + + *outputAngle = alpha; *outputValid = true; return returnvalue::OK; } // Will be the version in worst case scenario in event of no working MEKF (nor RMUs) -void SafeCtrl::safeNoMekf(timeval now, double *susDirB, bool *susDirBValid, double *sunRateB, - bool *sunRateBValid, double *magFieldB, bool *magFieldBValid, - double *magRateB, bool *magRateBValid, double *sunDirRef, - double *satRateRef, double *outputMagMomB, bool *outputValid) { +void SafeCtrl::safeNoMekf(timeval now, double *susDirB, bool susDirBValid, double *sunRateB, + bool sunRateBValid, double *magFieldB, bool magFieldBValid, + double *magRateB, bool magRateBValid, double *sunDirRef, + double *satRateRef, double *outputAngle, double *outputMagMomB, + bool *outputValid) { // Check for invalid Inputs if (!susDirBValid || !magFieldBValid || !magRateBValid) { *outputValid = false; return; } - // normalize sunDir and magDir + // normalize sunDir and magDir double magDirB[3] = {0, 0, 0}; VectorOperations::normalize(magFieldB, magDirB, 3); VectorOperations::normalize(susDirB, susDirB, 3); - // Cosinus angle between sunDir and magDir + // Cosinus angle between sunDir and magDir double cosAngleSunMag = VectorOperations::dot(magDirB, susDirB); - // Rate parallel to sun direction and magnetic field direction + // Rate parallel to sun direction and magnetic field direction double rateParaSun = 0, rateParaMag = 0; double dotSunRateMag = 0, dotmagRateSun = 0, rateFactor = 0; dotSunRateMag = VectorOperations::dot(sunRateB, magDirB); @@ -113,7 +116,7 @@ void SafeCtrl::safeNoMekf(timeval now, double *susDirB, bool *susDirBValid, doub rateParaSun = (dotmagRateSun + cosAngleSunMag * dotSunRateMag) / rateFactor; rateParaMag = (dotSunRateMag + cosAngleSunMag * dotmagRateSun) / rateFactor; - // Full rate or estimate + // Full rate or estimate double estSatRate[3] = {0, 0, 0}; double estSatRateMag[3] = {0, 0, 0}, estSatRateSun[3] = {0, 0, 0}; VectorOperations::mulScalar(susDirB, rateParaSun, estSatRateSun, 3); @@ -123,8 +126,8 @@ void SafeCtrl::safeNoMekf(timeval now, double *susDirB, bool *susDirBValid, doub VectorOperations::add(estSatRateSun, estSatRateMag, estSatRate, 3); VectorOperations::mulScalar(estSatRate, 0.5, estSatRate, 3); - /* Only valid if angle between sun direction and magnetic field direction - is sufficiently large */ + /* Only valid if angle between sun direction and magnetic field direction + is sufficiently large */ double sinAngle = 0; sinAngle = sin(acos(cos(cosAngleSunMag))); @@ -169,9 +172,7 @@ void SafeCtrl::safeNoMekf(timeval now, double *susDirB, bool *susDirBValid, doub double magMomFactor = pow(VectorOperations::norm(magFieldB, 3), 2); VectorOperations::mulScalar(crossMagFieldTorque, 1 / magMomFactor, magMomB, 3); - outputMagMomB[0] = magMomB[0]; - outputMagMomB[1] = magMomB[1]; - outputMagMomB[2] = magMomB[2]; - + std::memcpy(outputMagMomB, magMomB, 3 * sizeof(double)); + *outputAngle = angleAlignErr; *outputValid = true; } diff --git a/mission/controller/acs/control/SafeCtrl.h b/mission/controller/acs/control/SafeCtrl.h index 70426c9f..72e45f08 100644 --- a/mission/controller/acs/control/SafeCtrl.h +++ b/mission/controller/acs/control/SafeCtrl.h @@ -13,7 +13,6 @@ #include #include "../AcsParameters.h" -#include "../OutputValues.h" #include "../SensorValues.h" #include "../config/classIds.h" @@ -27,16 +26,16 @@ class SafeCtrl { 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, + ReturnValue_t safeMekf(timeval now, double *quatBJ, bool quatBJValid, double *magFieldModel, + bool magFieldModelValid, double *sunDirModel, bool sunDirModelValid, + double *satRateMekf, bool rateMekfValid, double *sunDirRef, double *satRatRef, // From Guidance (!) - double *outputMagMomB, bool *outputValid); + double *outputAngle, double *outputMagMomB, bool *outputValid); - void safeNoMekf(timeval now, double *susDirB, bool *susDirBValid, double *sunRateB, - bool *sunRateBValid, double *magFieldB, bool *magFieldBValid, double *magRateB, - bool *magRateBValid, double *sunDirRef, double *satRateRef, double *outputMagMomB, - bool *outputValid); + void safeNoMekf(timeval now, double *susDirB, bool susDirBValid, double *sunRateB, + bool sunRateBValid, double *magFieldB, bool magFieldBValid, double *magRateB, + bool magRateBValid, double *sunDirRef, double *satRateRef, double *outputAngle, + double *outputMagMomB, bool *outputValid); void idleSunPointing(); // with reaction wheels diff --git a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h index bb0a40ae..1b07218f 100644 --- a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h +++ b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h @@ -17,6 +17,7 @@ enum SetIds : uint32_t { GYR_PROCESSED_DATA, GPS_PROCESSED_DATA, MEKF_DATA, + CTRL_VAL_DATA, ACTUATOR_CMD_DATA }; @@ -88,6 +89,10 @@ enum PoolIds : lp_id_t { // MEKF SAT_ROT_RATE_MEKF, QUAT_MEKF, + // Ctrl Values + TGT_QUAT, + ERROR_QUAT, + ERROR_ANG, // Actuator Cmd RW_TARGET_TORQUE, RW_TARGET_SPEED, @@ -102,6 +107,7 @@ 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 = 2; static constexpr uint8_t MEKF_SET_ENTRIES = 2; +static constexpr uint8_t CTRL_VAL_SET_ENTRIES = 99; static constexpr uint8_t ACT_CMD_SET_ENTRIES = 3; /** @@ -133,9 +139,9 @@ class MgmDataProcessed : public StaticLocalDataSet { lp_vec_t mgm2vec = lp_vec_t(sid.objectId, MGM_2_VEC, this); lp_vec_t mgm3vec = lp_vec_t(sid.objectId, MGM_3_VEC, this); lp_vec_t mgm4vec = lp_vec_t(sid.objectId, MGM_4_VEC, this); - lp_vec_t mgmVecTot = lp_vec_t(sid.objectId, MGM_VEC_TOT, this); - lp_vec_t mgmVecTotDerivative = - lp_vec_t(sid.objectId, MGM_VEC_TOT_DERIVATIVE, this); + lp_vec_t mgmVecTot = lp_vec_t(sid.objectId, MGM_VEC_TOT, this); + lp_vec_t mgmVecTotDerivative = + lp_vec_t(sid.objectId, MGM_VEC_TOT_DERIVATIVE, this); lp_vec_t magIgrfModel = lp_vec_t(sid.objectId, MAG_IGRF_MODEL, this); private: @@ -179,9 +185,9 @@ class SusDataProcessed : public StaticLocalDataSet { lp_vec_t sus9vec = lp_vec_t(sid.objectId, SUS_8_VEC, this); lp_vec_t sus10vec = lp_vec_t(sid.objectId, SUS_8_VEC, this); lp_vec_t sus11vec = lp_vec_t(sid.objectId, SUS_8_VEC, this); - lp_vec_t susVecTot = lp_vec_t(sid.objectId, SUS_VEC_TOT, this); - lp_vec_t susVecTotDerivative = - lp_vec_t(sid.objectId, SUS_VEC_TOT_DERIVATIVE, this); + lp_vec_t susVecTot = lp_vec_t(sid.objectId, SUS_VEC_TOT, this); + lp_vec_t susVecTotDerivative = + lp_vec_t(sid.objectId, SUS_VEC_TOT_DERIVATIVE, this); lp_vec_t sunIjkModel = lp_vec_t(sid.objectId, SUN_IJK_MODEL, this); private: @@ -232,6 +238,17 @@ class MekfData : public StaticLocalDataSet { private: }; +class CtrlValData : public StaticLocalDataSet { + public: + CtrlValData(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, CTRL_VAL_DATA) {} + + lp_vec_t tgtQuat = lp_vec_t(sid.objectId, TGT_QUAT, this); + lp_vec_t errQuat = lp_vec_t(sid.objectId, ERROR_QUAT, this); + lp_var_t errAng = lp_var_t(sid.objectId, ERROR_ANG, this); + + private: +}; + class ActuatorCmdData : public StaticLocalDataSet { public: ActuatorCmdData(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, ACTUATOR_CMD_DATA) {} -- 2.34.1 From 4faf00de942d710f637ed4a4c2d2efa7934c12c1 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 3 Nov 2022 14:23:06 +0100 Subject: [PATCH 078/101] converted MTQ MGM readings from nT to uT --- mission/controller/acs/SensorProcessing.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index 1baa4007..bb445485 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -102,8 +102,10 @@ void SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const } } if (mgm4valid) { - VectorOperations::subtract(mgm4Value, mgmParameters->mgm4hardIronOffset, mgm4ValueNoBias, - 3); + float mgm4ValueNT[3]; + VectorOperations::mulScalar(mgm4Value, 1e3, mgm4ValueNT, 3); // uT to nT + VectorOperations::subtract(mgm4ValueNT, mgmParameters->mgm4hardIronOffset, + mgm4ValueNoBias, 3); MatrixOperations::multiply(mgmParameters->mgm4softIronInverse[0], mgm4ValueNoBias, mgm4ValueCalib, 3, 3, 1); MatrixOperations::multiply(mgmParameters->mgm4orientationMatrix[0], mgm4ValueCalib, -- 2.34.1 From c7bfe4002d7dcf16b13f3f375c225df080198b5f Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 3 Nov 2022 14:24:09 +0100 Subject: [PATCH 079/101] added event for SAFE to DETUMBLE transition. changed actuator input from double to int --- mission/controller/AcsController.cpp | 32 +++++++++++++------ mission/controller/AcsController.h | 4 +++ .../AcsCtrlDefinitions.h | 7 ++-- 3 files changed, 31 insertions(+), 12 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 953a91a1..799aa0c3 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -156,12 +156,13 @@ void AcsController::performSafe() { if (detumbleCounter > acsParameters.detumbleParameter.detumblecounter) { submode = SUBMODE_DETUMBLE; detumbleCounter = 0; + triggerEvent(SAFE_RATE_VIOLATION); } { PoolReadGuard pg(&actuatorCmdData); if (pg.getReadResult() == returnvalue::OK) { - double zeroVec[3] = {0, 0, 0, 0}; + double zeroVec[4] = {0, 0, 0, 0}; std::memcpy(actuatorCmdData.rwTargetTorque.value, zeroVec, 4 * sizeof(double)); actuatorCmdData.rwTargetTorque.setValid(false); std::memcpy(actuatorCmdData.rwTargetSpeed.value, zeroVec, 4 * sizeof(double)); @@ -175,8 +176,8 @@ void AcsController::performSafe() { // PoolReadGuard pg(&dipoleSet); // MutexGuard mg(torquer::lazyLock()); // torquer::NEW_ACTUATION_FLAG = true; - // dipoleSet.setDipoles(dipolCmdUnits[0], dipolCmdUnits[1], dipolCmdUnits[2], - //torqueDuration); + // dipoleSet.setDipoles(cmdDipolUnitsInt[0], cmdDipolUnitsInt[1], cmdDipolUnitsInt[2], + // torqueDuration); // } } @@ -215,15 +216,19 @@ void AcsController::performDetumble() { detumbleCounter = 0; } + int16_t cmdDipolUnitsInt[3] = {0, 0, 0}; + for (int i = 0; i < 3; ++i) { + cmdDipolUnitsInt[i] = std::round(dipolCmdUnits[i]); + } { PoolReadGuard pg(&actuatorCmdData); if (pg.getReadResult() == returnvalue::OK) { - double zeroVec[3] = {0, 0, 0, 0}; + double zeroVec[4] = {0, 0, 0, 0}; std::memcpy(actuatorCmdData.rwTargetTorque.value, zeroVec, 4 * sizeof(double)); actuatorCmdData.rwTargetTorque.setValid(false); std::memcpy(actuatorCmdData.rwTargetSpeed.value, zeroVec, 4 * sizeof(double)); actuatorCmdData.rwTargetSpeed.setValid(false); - std::memcpy(actuatorCmdData.mtqTargetDipole.value, dipolCmdUnits, 3 * sizeof(double)); + std::memcpy(actuatorCmdData.mtqTargetDipole.value, cmdDipolUnitsInt, 3 * sizeof(double)); actuatorCmdData.mtqTargetDipole.setValid(true); actuatorCmdData.setValidity(true, false); } @@ -232,7 +237,7 @@ void AcsController::performDetumble() { // PoolReadGuard pg(&dipoleSet); // MutexGuard mg(torquer::lazyLock()); // torquer::NEW_ACTUATION_FLAG = true; - // dipoleSet.setDipoles(dipolCmdUnits[0], dipolCmdUnits[1], dipolCmdUnits[2], + // dipoleSet.setDipoles(cmdDipolUnitsInt[0], cmdDipolUnitsInt[1], cmdDipolUnitsInt[2], // torqueDuration); // } } @@ -275,12 +280,21 @@ void AcsController::performPointingCtrl() { &(sensorValues.rw4Set.currSpeed.value), mgtDpDes); actuatorCmd.cmdDipolMtq(mgtDpDes, dipolUnits); + int16_t cmdDipolUnitsInt[3] = {0, 0, 0}; + for (int i = 0; i < 3; ++i) { + cmdDipolUnitsInt[i] = std::round(dipolUnits[i]); + } + int32_t cmdRwSpeedInt[4] = {0, 0, 0, 0}; + for (int i = 0; i < 4; ++i) { + cmdRwSpeedInt[i] = std::round(cmdSpeedRws[i]); + } + { PoolReadGuard pg(&actuatorCmdData); if (pg.getReadResult() == returnvalue::OK) { std::memcpy(actuatorCmdData.rwTargetTorque.value, rwTrqNs, 4 * sizeof(double)); - std::memcpy(actuatorCmdData.rwTargetSpeed.value, cmdSpeedRws, 4 * sizeof(double)); - std::memcpy(actuatorCmdData.mtqTargetDipole.value, dipolUnits, 3 * sizeof(double)); + std::memcpy(actuatorCmdData.rwTargetSpeed.value, cmdRwSpeedInt, 4 * sizeof(double)); + std::memcpy(actuatorCmdData.mtqTargetDipole.value, cmdDipolUnitsInt, 3 * sizeof(double)); actuatorCmdData.setValidity(true, true); } } @@ -288,7 +302,7 @@ void AcsController::performPointingCtrl() { // PoolReadGuard pg(&dipoleSet); // MutexGuard mg(torquer::lazyLock()); // torquer::NEW_ACTUATION_FLAG = true; - // dipoleSet.setDipoles(dipolCmdUnits[0], dipolCmdUnits[1], dipolCmdUnits[2], + // dipoleSet.setDipoles(cmdDipolUnitsInt[0], cmdDipolUnitsInt[1], cmdDipolUnitsInt[2], // torqueDuration); // } } diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index 18c8d824..7f6363ce 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -30,6 +30,10 @@ class AcsController : public ExtendedControllerBase { static const Submode_t SUBMODE_PTG_NADIR = 5; static const Submode_t SUBMODE_PTG_INERTIAL = 6; + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::ACS_SUBSYSTEM; + static const Event SAFE_RATE_VIOLATION = + MAKE_EVENT(0, severity::MEDIUM); //!< The limits for the rotation in safe mode were violated. + protected: void performSafe(); void performDetumble(); diff --git a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h index 1b07218f..2652ca3c 100644 --- a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h +++ b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h @@ -107,7 +107,7 @@ 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 = 2; static constexpr uint8_t MEKF_SET_ENTRIES = 2; -static constexpr uint8_t CTRL_VAL_SET_ENTRIES = 99; +static constexpr uint8_t CTRL_VAL_SET_ENTRIES = 3; static constexpr uint8_t ACT_CMD_SET_ENTRIES = 3; /** @@ -254,8 +254,9 @@ class ActuatorCmdData : public StaticLocalDataSet { ActuatorCmdData(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, ACTUATOR_CMD_DATA) {} lp_vec_t rwTargetTorque = lp_vec_t(sid.objectId, RW_TARGET_TORQUE, this); - lp_vec_t rwTargetSpeed = lp_vec_t(sid.objectId, RW_TARGET_SPEED, this); - lp_vec_t mtqTargetDipole = lp_vec_t(sid.objectId, MTQ_TARGET_DIPOLE, this); + lp_vec_t rwTargetSpeed = lp_vec_t(sid.objectId, RW_TARGET_SPEED, this); + lp_vec_t mtqTargetDipole = + lp_vec_t(sid.objectId, MTQ_TARGET_DIPOLE, this); private: }; -- 2.34.1 From a4735defaaeba3a827cb69c245bf5b0f21f21b7b Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Fri, 4 Nov 2022 12:41:35 +0100 Subject: [PATCH 080/101] amended gyr sensor fusion --- mission/controller/acs/AcsParameters.h | 2 + mission/controller/acs/SensorProcessing.cpp | 65 +++++++-------------- 2 files changed, 23 insertions(+), 44 deletions(-) diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index f5b72252..813851dc 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -762,6 +762,8 @@ class AcsParameters /*: public HasParametersIF*/ { pow(3.0e-3 * sqrt(2), 2), // RND_y = 3.0e-3 deg/s/sqrt(Hz) rms pow(4.3e-3 * sqrt(2), 2)}; // RND_z = 4.3e-3 deg/s/sqrt(Hz) rms float gyr13variance[3] = {pow(11e-3, 2), pow(11e-3, 2), pow(11e-3, 2)}; + enum PreferAdis { NO = 0, YES = 1 }; + uint8_t preferAdis = PreferAdis::YES; } gyrHandlingParameters; struct RwHandlingParameters { diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index bb445485..483b94c2 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -480,80 +480,57 @@ void SensorProcessing::processGyr( // Transforming Values to the Body Frame (actually it is the geometry frame atm) double gyr0ValueBody[3] = {0, 0, 0}, gyr1ValueBody[3] = {0, 0, 0}, gyr2ValueBody[3] = {0, 0, 0}, gyr3ValueBody[3] = {0, 0, 0}; + float sensorFusionNumerator[3] = {0, 0, 0}, sensorFusionDenominator[3] = {0, 0, 0}; if (gyr0valid) { const double gyr0Value[3] = {gyr0axXvalue, gyr0axYvalue, gyr0axZvalue}; MatrixOperations::multiply(gyrParameters->gyr0orientationMatrix[0], gyr0Value, gyr0ValueBody, 3, 3, 1); + for (uint8_t i = 0; i < 3; i++) { + sensorFusionNumerator[i] += gyr0ValueBody[i] / gyrParameters->gyr02variance[i]; + sensorFusionDenominator[i] += 1 / gyrParameters->gyr02variance[i]; + } } if (gyr1valid) { const double gyr1Value[3] = {gyr1axXvalue, gyr1axYvalue, gyr1axZvalue}; MatrixOperations::multiply(gyrParameters->gyr1orientationMatrix[0], gyr1Value, gyr1ValueBody, 3, 3, 1); + for (uint8_t i = 0; i < 3; i++) { + sensorFusionNumerator[i] += gyr1ValueBody[i] / gyrParameters->gyr13variance[i]; + sensorFusionDenominator[i] += 1 / gyrParameters->gyr13variance[i]; + } } if (gyr2valid) { const double gyr2Value[3] = {gyr2axXvalue, gyr2axYvalue, gyr2axZvalue}; MatrixOperations::multiply(gyrParameters->gyr2orientationMatrix[0], gyr2Value, gyr2ValueBody, 3, 3, 1); + for (uint8_t i = 0; i < 3; i++) { + sensorFusionNumerator[i] += gyr2ValueBody[i] / gyrParameters->gyr02variance[i]; + sensorFusionDenominator[i] += 1 / gyrParameters->gyr02variance[i]; + } } if (gyr3valid) { const double gyr3Value[3] = {gyr3axXvalue, gyr3axYvalue, gyr3axZvalue}; MatrixOperations::multiply(gyrParameters->gyr3orientationMatrix[0], gyr3Value, gyr3ValueBody, 3, 3, 1); + for (uint8_t i = 0; i < 3; i++) { + sensorFusionNumerator[i] += gyr3ValueBody[i] / gyrParameters->gyr13variance[i]; + sensorFusionDenominator[i] += 1 / gyrParameters->gyr13variance[i]; + } } /* -------- SatRateEst: Middle Value ------- */ // take ADIS measurements, if both avail // if just one ADIS measurement avail, perform sensor fusion double gyrVecTot[3] = {0.0, 0.0, 0.0}; - if (gyr0valid && gyr2valid) { + if ((gyr0valid && gyr2valid) && gyrParameters->preferAdis == gyrParameters->PreferAdis::YES) { double gyr02ValuesSum[3]; VectorOperations::add(gyr0ValueBody, gyr2ValueBody, gyr02ValuesSum, 3); VectorOperations::mulScalar(gyr02ValuesSum, .5, gyrVecTot, 3); - } else if ((gyr0valid || gyr2valid) && !(gyr1valid || gyr3valid)) { - if (gyr0valid) { - std::memcpy(gyrVecTot, gyr0ValueBody, 3 * sizeof(double)); - } else if (gyr2valid) { - std::memcpy(gyrVecTot, gyr2ValueBody, 3 * sizeof(double)); + } else { + for (uint8_t i = 0; i < 3; i++) { + gyrVecTot[i] = sensorFusionNumerator[i] / sensorFusionDenominator[i]; } - } else if (gyr1valid && gyr3valid) { - double gyr13ValuesSum[3]; - double gyr13ValuesMean[3]; - VectorOperations::add(gyr1ValueBody, gyr3ValueBody, gyr13ValuesSum, 3); - VectorOperations::mulScalar(gyr13ValuesSum, .5, gyr13ValuesMean, 3); - if (gyr0valid) { - gyrVecTot[0] = - ((gyr0ValueBody[0] / gyrParameters->gyr02variance[0]) + - (gyr13ValuesMean[0] / gyrParameters->gyr13variance[0])) / - ((1 / gyrParameters->gyr02variance[0]) + (1 / gyrParameters->gyr13variance[0])); - gyrVecTot[1] = - ((gyr0ValueBody[1] / gyrParameters->gyr02variance[1]) + - (gyr13ValuesMean[1] / gyrParameters->gyr13variance[1])) / - ((1 / gyrParameters->gyr02variance[1]) + (1 / gyrParameters->gyr13variance[1])); - gyrVecTot[2] = - ((gyr0ValueBody[2] / gyrParameters->gyr02variance[2]) + - (gyr13ValuesMean[2] / gyrParameters->gyr13variance[2])) / - ((1 / gyrParameters->gyr02variance[2]) + (1 / gyrParameters->gyr13variance[2])); - } else if (gyr2valid) { - gyrVecTot[0] = - ((gyr2ValueBody[0] / gyrParameters->gyr02variance[0]) + - (gyr13ValuesMean[0] / gyrParameters->gyr13variance[0])) / - ((1 / gyrParameters->gyr02variance[0]) + (1 / gyrParameters->gyr13variance[0])); - gyrVecTot[1] = - ((gyr2ValueBody[1] / gyrParameters->gyr02variance[1]) + - (gyr13ValuesMean[1] / gyrParameters->gyr13variance[1])) / - ((1 / gyrParameters->gyr02variance[1]) + (1 / gyrParameters->gyr13variance[1])); - gyrVecTot[2] = - ((gyr2ValueBody[2] / gyrParameters->gyr02variance[2]) + - (gyr13ValuesMean[2] / gyrParameters->gyr13variance[2])) / - ((1 / gyrParameters->gyr02variance[2]) + (1 / gyrParameters->gyr13variance[2])); - } else { - std::memcpy(gyrVecTot, gyr13ValuesMean, 3 * sizeof(double)); - } - } else if (gyr1valid) { - std::memcpy(gyrVecTot, gyr1ValueBody, 3 * sizeof(double)); - } else if (gyr3valid) { - std::memcpy(gyrVecTot, gyr3ValueBody, 3 * sizeof(double)); } { PoolReadGuard pg(gyrDataProcessed); -- 2.34.1 From d184f7487e6cead6705c31d0190f2c2e8eb86379 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Fri, 4 Nov 2022 14:54:23 +0100 Subject: [PATCH 081/101] post merge cleanup --- bsp_q7s/core/InitMission.cpp | 46 ++++++++++++------------ fsfw | 2 +- mission/controller/AcsController.cpp | 1 - mission/controller/AcsController.h | 1 - mission/controller/acs/SensorValues.h | 4 +-- mission/controller/acs/config/classIds.h | 9 +---- 6 files changed, 26 insertions(+), 37 deletions(-) diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index 4938b991..b922ae88 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -163,29 +163,29 @@ void initmission::initTasks() { } #endif #if OBSW_Q7S_EM == 1 - acsTask->addComponent(objects::MGM_0_LIS3_HANDLER); - acsTask->addComponent(objects::MGM_1_RM3100_HANDLER); - acsTask->addComponent(objects::MGM_2_LIS3_HANDLER); - acsTask->addComponent(objects::MGM_3_RM3100_HANDLER); - acsTask->addComponent(objects::IMTQ_HANDLER); - acsTask->addComponent(objects::SUS_0_N_LOC_XFYFZM_PT_XF); - acsTask->addComponent(objects::SUS_6_R_LOC_XFYBZM_PT_XF); - acsTask->addComponent(objects::SUS_1_N_LOC_XBYFZM_PT_XB); - acsTask->addComponent(objects::SUS_7_R_LOC_XBYBZM_PT_XB); - acsTask->addComponent(objects::SUS_2_N_LOC_XFYBZB_PT_YB); - acsTask->addComponent(objects::SUS_8_R_LOC_XBYBZB_PT_YB); - acsTask->addComponent(objects::SUS_3_N_LOC_XFYBZF_PT_YF); - acsTask->addComponent(objects::SUS_9_R_LOC_XBYBZB_PT_YF); - acsTask->addComponent(objects::SUS_4_N_LOC_XMYFZF_PT_ZF); - acsTask->addComponent(objects::SUS_10_N_LOC_XMYBZF_PT_ZF); - acsTask->addComponent(objects::SUS_5_N_LOC_XFYMZB_PT_ZB); - acsTask->addComponent(objects::SUS_11_R_LOC_XBYMZB_PT_ZB); - acsTask->addComponent(objects::GYRO_0_ADIS_HANDLER); - acsTask->addComponent(objects::GYRO_1_L3G_HANDLER); - acsTask->addComponent(objects::GYRO_2_ADIS_HANDLER); - acsTask->addComponent(objects::GYRO_3_L3G_HANDLER); - acsTask->addComponent(objects::GPS_CONTROLLER); - acsTask->addComponent(objects::STAR_TRACKER); + acsCtrlTask->addComponent(objects::MGM_0_LIS3_HANDLER); + acsCtrlTask->addComponent(objects::MGM_1_RM3100_HANDLER); + acsCtrlTask->addComponent(objects::MGM_2_LIS3_HANDLER); + acsCtrlTask->addComponent(objects::MGM_3_RM3100_HANDLER); + acsCtrlTask->addComponent(objects::IMTQ_HANDLER); + acsCtrlTask->addComponent(objects::SUS_0_N_LOC_XFYFZM_PT_XF); + acsCtrlTask->addComponent(objects::SUS_6_R_LOC_XFYBZM_PT_XF); + acsCtrlTask->addComponent(objects::SUS_1_N_LOC_XBYFZM_PT_XB); + acsCtrlTask->addComponent(objects::SUS_7_R_LOC_XBYBZM_PT_XB); + acsCtrlTask->addComponent(objects::SUS_2_N_LOC_XFYBZB_PT_YB); + acsCtrlTask->addComponent(objects::SUS_8_R_LOC_XBYBZB_PT_YB); + acsCtrlTask->addComponent(objects::SUS_3_N_LOC_XFYBZF_PT_YF); + acsCtrlTask->addComponent(objects::SUS_9_R_LOC_XBYBZB_PT_YF); + acsCtrlTask->addComponent(objects::SUS_4_N_LOC_XMYFZF_PT_ZF); + acsCtrlTask->addComponent(objects::SUS_10_N_LOC_XMYBZF_PT_ZF); + acsCtrlTask->addComponent(objects::SUS_5_N_LOC_XFYMZB_PT_ZB); + acsCtrlTask->addComponent(objects::SUS_11_R_LOC_XBYMZB_PT_ZB); + acsCtrlTask->addComponent(objects::GYRO_0_ADIS_HANDLER); + acsCtrlTask->addComponent(objects::GYRO_1_L3G_HANDLER); + acsCtrlTask->addComponent(objects::GYRO_2_ADIS_HANDLER); + acsCtrlTask->addComponent(objects::GYRO_3_L3G_HANDLER); + acsCtrlTask->addComponent(objects::GPS_CONTROLLER); + acsCtrlTask->addComponent(objects::STAR_TRACKER); #endif PeriodicTaskIF* acsSysTask = factory->createPeriodicTask( diff --git a/fsfw b/fsfw index 7e0a5d5a..672fca51 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 7e0a5d5a9e4f38c6d818bbdd5b44d34d8007eb1e +Subproject commit 672fca5169b017387e58e2ff864913d932c59aa1 diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 4134a38d..0c2b58a9 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -637,4 +637,3 @@ void AcsController::copyGyrData() { } } } - diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index 1fd04aa2..cfcc200d 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -1,7 +1,6 @@ #ifndef MISSION_CONTROLLER_ACSCONTROLLER_H_ #define MISSION_CONTROLLER_ACSCONTROLLER_H_ -#include #include #include diff --git a/mission/controller/acs/SensorValues.h b/mission/controller/acs/SensorValues.h index 1a260635..ef897207 100644 --- a/mission/controller/acs/SensorValues.h +++ b/mission/controller/acs/SensorValues.h @@ -1,17 +1,15 @@ #ifndef SENSORVALUES_H_ #define SENSORVALUES_H_ -#include - #include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" #include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" #include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" #include "mission/devices/devicedefinitions/GPSDefinitions.h" #include "mission/devices/devicedefinitions/GyroADIS1650XDefinitions.h" #include "mission/devices/devicedefinitions/GyroL3GD20Definitions.h" -#include "mission/devices/devicedefinitions/IMTQHandlerDefinitions.h" #include "mission/devices/devicedefinitions/RwDefinitions.h" #include "mission/devices/devicedefinitions/SusDefinitions.h" +#include "mission/devices/devicedefinitions/imtqHandlerDefinitions.h" namespace ACS { diff --git a/mission/controller/acs/config/classIds.h b/mission/controller/acs/config/classIds.h index 7db1ea72..e714ff33 100644 --- a/mission/controller/acs/config/classIds.h +++ b/mission/controller/acs/config/classIds.h @@ -1,14 +1,7 @@ -/* - * classIds.h - * - * Created on: 1 Mar 2022 - * Author: rooob - */ - #ifndef ACS_CONFIG_CLASSIDS_H_ #define ACS_CONFIG_CLASSIDS_H_ -#include +#include #include namespace CLASS_ID { -- 2.34.1 From 8cc368b131cc0d300353f2ef3ab49b84d74eb6c4 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 8 Nov 2022 10:56:12 +0100 Subject: [PATCH 082/101] fixed types for actuatorCmdData --- mission/controller/AcsController.cpp | 27 +++++++++++++-------------- mission/controller/AcsController.h | 4 ++-- 2 files changed, 15 insertions(+), 16 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 0c2b58a9..d00bb816 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -164,22 +164,21 @@ void AcsController::performSafe() { { PoolReadGuard pg(&actuatorCmdData); if (pg.getReadResult() == returnvalue::OK) { - double zeroVec[4] = {0, 0, 0, 0}; - std::memcpy(actuatorCmdData.rwTargetTorque.value, zeroVec, 4 * sizeof(double)); + int32_t zeroVec[4] = {0, 0, 0, 0}; + std::memcpy(actuatorCmdData.rwTargetTorque.value, zeroVec, 4 * sizeof(int32_t)); actuatorCmdData.rwTargetTorque.setValid(false); - std::memcpy(actuatorCmdData.rwTargetSpeed.value, zeroVec, 4 * sizeof(double)); + std::memcpy(actuatorCmdData.rwTargetSpeed.value, zeroVec, 4 * sizeof(int32_t)); actuatorCmdData.rwTargetSpeed.setValid(false); - std::memcpy(actuatorCmdData.mtqTargetDipole.value, dipolCmdUnits, 3 * sizeof(double)); + std::memcpy(actuatorCmdData.mtqTargetDipole.value, dipolCmdUnits, 3 * sizeof(int16_t)); actuatorCmdData.mtqTargetDipole.setValid(true); actuatorCmdData.setValidity(true, false); } } // { - // PoolReadGuard pg(&dipoleSet); - // MutexGuard mg(torquer::lazyLock()); - // torquer::NEW_ACTUATION_FLAG = true; - // dipoleSet.setDipoles(cmdDipolUnitsInt[0], cmdDipolUnitsInt[1], cmdDipolUnitsInt[2], - // torqueDuration); + // PoolReadGuard pg(&dipoleSet); + // MutexGuard mg(torquer::lazyLock()); + // torquer::NEW_ACTUATION_FLAG = true; + // dipoleSet.setDipoles(cmdDipolUnits[0], cmdDipolUnits[1], cmdDipolUnits[2], torqueDuration); // } } @@ -225,12 +224,12 @@ void AcsController::performDetumble() { { PoolReadGuard pg(&actuatorCmdData); if (pg.getReadResult() == returnvalue::OK) { - double zeroVec[4] = {0, 0, 0, 0}; + int32_t zeroVec[4] = {0, 0, 0, 0}; std::memcpy(actuatorCmdData.rwTargetTorque.value, zeroVec, 4 * sizeof(double)); actuatorCmdData.rwTargetTorque.setValid(false); - std::memcpy(actuatorCmdData.rwTargetSpeed.value, zeroVec, 4 * sizeof(double)); + std::memcpy(actuatorCmdData.rwTargetSpeed.value, zeroVec, 4 * sizeof(int32_t)); actuatorCmdData.rwTargetSpeed.setValid(false); - std::memcpy(actuatorCmdData.mtqTargetDipole.value, cmdDipolUnitsInt, 3 * sizeof(double)); + std::memcpy(actuatorCmdData.mtqTargetDipole.value, cmdDipolUnitsInt, 3 * sizeof(int16_t)); actuatorCmdData.mtqTargetDipole.setValid(true); actuatorCmdData.setValidity(true, false); } @@ -295,8 +294,8 @@ void AcsController::performPointingCtrl() { PoolReadGuard pg(&actuatorCmdData); if (pg.getReadResult() == returnvalue::OK) { std::memcpy(actuatorCmdData.rwTargetTorque.value, rwTrqNs, 4 * sizeof(double)); - std::memcpy(actuatorCmdData.rwTargetSpeed.value, cmdRwSpeedInt, 4 * sizeof(double)); - std::memcpy(actuatorCmdData.mtqTargetDipole.value, cmdDipolUnitsInt, 3 * sizeof(double)); + std::memcpy(actuatorCmdData.rwTargetSpeed.value, cmdRwSpeedInt, 4 * sizeof(int32_t)); + std::memcpy(actuatorCmdData.mtqTargetDipole.value, cmdDipolUnitsInt, 3 * sizeof(int16_t)); actuatorCmdData.setValidity(true, true); } } diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index cfcc200d..ed896d8e 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -158,8 +158,8 @@ IMTQ::DipoleActuationSet dipoleSet = IMTQ::DipoleActuationSet(objects::IMTQ_HAND // Actuator CMD acsctrl::ActuatorCmdData actuatorCmdData; PoolEntry rwTargetTorque = PoolEntry(4); - PoolEntry rwTargetSpeed = PoolEntry(4); - PoolEntry mtqTargetDipole = PoolEntry(3); + PoolEntry rwTargetSpeed = PoolEntry(4); + PoolEntry mtqTargetDipole = PoolEntry(3); // Initial delay to make sure all pool variables have been initialized their owners Countdown initialCountdown = Countdown(INIT_DELAY); -- 2.34.1 From ca9ef281996a88f0fa45ada816fcfe420087660f Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 10 Nov 2022 16:31:59 +0100 Subject: [PATCH 083/101] dummy stuff --- dummies/GpsDummy.cpp | 4 ++-- dummies/SusDummy.cpp | 22 ++++++++++++---------- dummies/SusDummy.h | 2 +- 3 files changed, 15 insertions(+), 13 deletions(-) diff --git a/dummies/GpsDummy.cpp b/dummies/GpsDummy.cpp index d1f526d2..893e8464 100644 --- a/dummies/GpsDummy.cpp +++ b/dummies/GpsDummy.cpp @@ -37,8 +37,8 @@ uint32_t GpsDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return ReturnValue_t GpsDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { - localDataPoolMap.emplace(GpsHyperion::LATITUDE, new PoolEntry({0.0})); - localDataPoolMap.emplace(GpsHyperion::LONGITUDE, new PoolEntry({0.0})); + localDataPoolMap.emplace(GpsHyperion::LATITUDE, new PoolEntry({0.0}, 1)); + localDataPoolMap.emplace(GpsHyperion::LONGITUDE, new PoolEntry({0.0}, 1)); localDataPoolMap.emplace(GpsHyperion::ALTITUDE, new PoolEntry({0.0})); localDataPoolMap.emplace(GpsHyperion::SPEED, new PoolEntry({7684.2})); localDataPoolMap.emplace(GpsHyperion::FIX_MODE, new PoolEntry({0})); diff --git a/dummies/SusDummy.cpp b/dummies/SusDummy.cpp index 706f08f0..46b2ec68 100644 --- a/dummies/SusDummy.cpp +++ b/dummies/SusDummy.cpp @@ -1,5 +1,7 @@ + #include "SusDummy.h" +#include #include #include @@ -28,7 +30,6 @@ ReturnValue_t SusDummy::initialize() { return result; } } - return returnvalue::OK; } @@ -37,29 +38,30 @@ ReturnValue_t SusDummy::handleCommandMessage(CommandMessage* message) { } void SusDummy::performControlOperation() { - iteration++; - value = sin(iteration / 80. * M_PI + 10) * 10 - 10; + // value = sin(iteration / 80. * M_PI + 10) * 10 - 10; susSet.read(); -// susSet.temperatureCelcius = value; -// if ((iteration % 100) < 20) { -// susSet.setValidity(false, true); -// } else { -// susSet.setValidity(true, true); -// } + // susSet.temperatureCelcius = value; + // if ((iteration % 100) < 20) { + // susSet.setValidity(false, true); + // } else { + // susSet.setValidity(true, true); + // } susSet.channels[0] = 3913; susSet.channels[1] = 3912; susSet.channels[2] = 3799; susSet.channels[3] = 3797; susSet.channels[4] = 4056; + susSet.setValidity(true, true); susSet.commit(); + iteration++; } ReturnValue_t SusDummy::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) { localDataPoolMap.emplace(SUS::SusPoolIds::TEMPERATURE_C, new PoolEntry({0}, 1, true)); localDataPoolMap.emplace(SUS::SusPoolIds::CHANNEL_VEC, - new PoolEntry({0, 0, 0, 0, 0, 0},true)); + new PoolEntry({0, 0, 0, 0, 0, 0}, true)); return returnvalue::OK; } diff --git a/dummies/SusDummy.h b/dummies/SusDummy.h index bdabaafc..3e24f368 100644 --- a/dummies/SusDummy.h +++ b/dummies/SusDummy.h @@ -24,4 +24,4 @@ class SusDummy : public ExtendedControllerBase { int iteration = 0; float value = 0; SUS::SusDataset susSet; -}; \ No newline at end of file +}; -- 2.34.1 From c430caadd7446e46cf59ee9cd2d32c202072570c Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 17 Nov 2022 12:00:53 +0100 Subject: [PATCH 084/101] changed SusDummies from ExtendedController to DeviceHandler --- dummies/SusDummy.cpp | 102 ++++++++++++------------------------------- dummies/SusDummy.h | 47 ++++++++++++-------- dummies/helpers.cpp | 17 ++++++-- 3 files changed, 71 insertions(+), 95 deletions(-) diff --git a/dummies/SusDummy.cpp b/dummies/SusDummy.cpp index 46b2ec68..28f85969 100644 --- a/dummies/SusDummy.cpp +++ b/dummies/SusDummy.cpp @@ -1,87 +1,43 @@ - #include "SusDummy.h" -#include -#include +SusDummy::SusDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) + : DeviceHandlerBase(objectId, comif, comCookie), susSet(this) {} -#include -#include +SusDummy::~SusDummy() {} -SusDummy::SusDummy() : ExtendedControllerBase(objects::SUS_0_N_LOC_XFYFZM_PT_XF), susSet(this) { - ObjectManager::instance()->insert(objects::SUS_6_R_LOC_XFYBZM_PT_XF, this); - ObjectManager::instance()->insert(objects::SUS_1_N_LOC_XBYFZM_PT_XB, this); - ObjectManager::instance()->insert(objects::SUS_7_R_LOC_XBYBZM_PT_XB, this); - ObjectManager::instance()->insert(objects::SUS_2_N_LOC_XFYBZB_PT_YB, this); - ObjectManager::instance()->insert(objects::SUS_8_R_LOC_XBYBZB_PT_YB, this); - ObjectManager::instance()->insert(objects::SUS_3_N_LOC_XFYBZF_PT_YF, this); - ObjectManager::instance()->insert(objects::SUS_9_R_LOC_XBYBZB_PT_YF, this); - ObjectManager::instance()->insert(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, this); - ObjectManager::instance()->insert(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, this); - ObjectManager::instance()->insert(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, this); - ObjectManager::instance()->insert(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, this); +void SusDummy::doStartUp() {} + +void SusDummy::doShutDown() {} + +ReturnValue_t SusDummy::buildNormalDeviceCommand(DeviceCommandId_t *id) { return NOTHING_TO_SEND; } + +ReturnValue_t SusDummy::buildTransitionDeviceCommand(DeviceCommandId_t *id) { + return NOTHING_TO_SEND; } -ReturnValue_t SusDummy::initialize() { - static bool done = false; - if (not done) { - done = true; - ReturnValue_t result = ExtendedControllerBase::initialize(); - if (result != returnvalue::OK) { - return result; - } - } +ReturnValue_t SusDummy::buildCommandFromCommand(DeviceCommandId_t deviceCommand, + const uint8_t *commandData, size_t commandDataLen) { return returnvalue::OK; } -ReturnValue_t SusDummy::handleCommandMessage(CommandMessage* message) { - return returnvalue::FAILED; -} - -void SusDummy::performControlOperation() { - // value = sin(iteration / 80. * M_PI + 10) * 10 - 10; - - susSet.read(); - // susSet.temperatureCelcius = value; - // if ((iteration % 100) < 20) { - // susSet.setValidity(false, true); - // } else { - // susSet.setValidity(true, true); - // } - susSet.channels[0] = 3913; - susSet.channels[1] = 3912; - susSet.channels[2] = 3799; - susSet.channels[3] = 3797; - susSet.channels[4] = 4056; - susSet.setValidity(true, true); - susSet.commit(); - iteration++; -} - -ReturnValue_t SusDummy::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) { - localDataPoolMap.emplace(SUS::SusPoolIds::TEMPERATURE_C, new PoolEntry({0}, 1, true)); - localDataPoolMap.emplace(SUS::SusPoolIds::CHANNEL_VEC, - new PoolEntry({0, 0, 0, 0, 0, 0}, true)); - +ReturnValue_t SusDummy::scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) { return returnvalue::OK; } -LocalPoolDataSetBase* SusDummy::getDataSetHandle(sid_t sid) { - switch (sid.ownerSetId) { - case SUS::SUS_DATA_SET_ID: - return &susSet; - default: - return nullptr; - } -} - -ReturnValue_t SusDummy::checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t* msToReachTheMode) { - if (submode != SUBMODE_NONE) { - return INVALID_SUBMODE; - } - if ((mode != MODE_OFF) && (mode != MODE_ON) && (mode != MODE_NORMAL)) { - return INVALID_MODE; - } +ReturnValue_t SusDummy::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) { return returnvalue::OK; } + +void SusDummy::fillCommandAndReplyMap() {} + +uint32_t SusDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } + +ReturnValue_t SusDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) { + localDataPoolMap.emplace(SUS::SusPoolIds::TEMPERATURE_C, new PoolEntry({0}, 1, true)); + localDataPoolMap.emplace(SUS::SusPoolIds::CHANNEL_VEC, + new PoolEntry({0, 0, 0, 0, 0, 0},true)); + + return returnvalue::OK; +} diff --git a/dummies/SusDummy.h b/dummies/SusDummy.h index 3e24f368..a229bd87 100644 --- a/dummies/SusDummy.h +++ b/dummies/SusDummy.h @@ -1,27 +1,36 @@ -#pragma once +#ifndef DUMMIES_SUSDUMMY_H_ +#define DUMMIES_SUSDUMMY_H_ -#include -#include +#include -class SusDummy : public ExtendedControllerBase { +#include "mission/devices/devicedefinitions/SusDefinitions.h" + +class SusDummy : public DeviceHandlerBase { public: - SusDummy(); + static const DeviceCommandId_t SIMPLE_COMMAND = 1; + static const DeviceCommandId_t PERIODIC_REPLY = 2; - ReturnValue_t initialize() override; + static const uint8_t SIMPLE_COMMAND_DATA = 1; + static const uint8_t PERIODIC_REPLY_DATA = 2; + + SusDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie); + virtual ~SusDummy(); protected: - virtual ReturnValue_t handleCommandMessage(CommandMessage* message) override; - virtual void performControlOperation() override; - virtual ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, - LocalDataPoolManager& poolManager) override; - virtual LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override; - - // Mode abstract functions - virtual ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, - uint32_t* msToReachTheMode) override; - - private: - int iteration = 0; - float value = 0; SUS::SusDataset susSet; + void doStartUp() override; + void doShutDown() override; + ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id) override; + ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t *commandData, + size_t commandDataLen) override; + ReturnValue_t scanForReply(const uint8_t *start, size_t len, DeviceCommandId_t *foundId, + size_t *foundLen) override; + ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override; + void fillCommandAndReplyMap() override; + uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; + ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap, + LocalDataPoolManager &poolManager) override; }; + +#endif /* DUMMIES_SUSDUMMY_H_ */ diff --git a/dummies/helpers.cpp b/dummies/helpers.cpp index ef144dc6..8d8ac70b 100644 --- a/dummies/helpers.cpp +++ b/dummies/helpers.cpp @@ -1,3 +1,5 @@ +#include "helpers.h" + #include #include #include @@ -19,8 +21,6 @@ #include #include -#include "helpers.h" - using namespace dummy; void dummy::createDummies(DummyCfg cfg) { @@ -63,7 +63,18 @@ void dummy::createDummies(DummyCfg cfg) { } if (cfg.addSusDummies) { - new SusDummy(); + new SusDummy(objects::SUS_0_N_LOC_XFYFZM_PT_XF, objects::DUMMY_COM_IF, comCookieDummy); + new SusDummy(objects::SUS_1_N_LOC_XBYFZM_PT_XB, objects::DUMMY_COM_IF, comCookieDummy); + new SusDummy(objects::SUS_2_N_LOC_XFYBZB_PT_YB, objects::DUMMY_COM_IF, comCookieDummy); + new SusDummy(objects::SUS_3_N_LOC_XFYBZF_PT_YF, objects::DUMMY_COM_IF, comCookieDummy); + new SusDummy(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, objects::DUMMY_COM_IF, comCookieDummy); + new SusDummy(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, objects::DUMMY_COM_IF, comCookieDummy); + new SusDummy(objects::SUS_6_R_LOC_XFYBZM_PT_XF, objects::DUMMY_COM_IF, comCookieDummy); + new SusDummy(objects::SUS_7_R_LOC_XBYBZM_PT_XB, objects::DUMMY_COM_IF, comCookieDummy); + new SusDummy(objects::SUS_8_R_LOC_XBYBZB_PT_YB, objects::DUMMY_COM_IF, comCookieDummy); + new SusDummy(objects::SUS_9_R_LOC_XBYBZB_PT_YF, objects::DUMMY_COM_IF, comCookieDummy); + new SusDummy(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, objects::DUMMY_COM_IF, comCookieDummy); + new SusDummy(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, objects::DUMMY_COM_IF, comCookieDummy); } if (cfg.addTempSensorDummies) { -- 2.34.1 From f3ac6d4a7e03658e45b588b496115838f36850ff Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 17 Nov 2022 13:01:29 +0100 Subject: [PATCH 085/101] added GPS and RW sensor readings. added RW1..4 dummies to acsTask --- bsp_q7s/core/InitMission.cpp | 4 ++++ mission/controller/acs/SensorValues.cpp | 5 ++++- 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index b922ae88..1406c375 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -186,6 +186,10 @@ void initmission::initTasks() { acsCtrlTask->addComponent(objects::GYRO_3_L3G_HANDLER); acsCtrlTask->addComponent(objects::GPS_CONTROLLER); acsCtrlTask->addComponent(objects::STAR_TRACKER); + acsCtrlTask->addComponent(objects::RW1); + acsCtrlTask->addComponent(objects::RW2); + acsCtrlTask->addComponent(objects::RW3); + acsCtrlTask->addComponent(objects::RW4); #endif PeriodicTaskIF* acsSysTask = factory->createPeriodicTask( diff --git a/mission/controller/acs/SensorValues.cpp b/mission/controller/acs/SensorValues.cpp index 18f0d16f..568a9e1c 100644 --- a/mission/controller/acs/SensorValues.cpp +++ b/mission/controller/acs/SensorValues.cpp @@ -82,8 +82,11 @@ ReturnValue_t SensorValues::update() { ReturnValue_t susUpdate = updateSus(); ReturnValue_t gyrUpdate = updateGyr(); ReturnValue_t strUpdate = updateStr(); + ReturnValue_t gpsUpdate = updateGps(); + ReturnValue_t rwUpdate = updateRw(); - if ((mgmUpdate && susUpdate && gyrUpdate && strUpdate) == returnvalue::FAILED) { + if ((mgmUpdate && susUpdate && gyrUpdate && strUpdate && gpsUpdate && rwUpdate) == + returnvalue::FAILED) { return returnvalue::FAILED; }; return returnvalue::OK; -- 2.34.1 From 281eb3237cb489bc8d29d4484d0b4f2f3128e936 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 17 Nov 2022 15:55:30 +0100 Subject: [PATCH 086/101] fixed susTotVec and mgmTotVec types to dataSet types --- mission/controller/acs/SensorProcessing.cpp | 29 ++++++++++++++------- 1 file changed, 19 insertions(+), 10 deletions(-) diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index 483b94c2..407ba900 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -115,13 +115,13 @@ void SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const sensorFusionDenominator[i] += 1 / mgmParameters->mgm4variance[i]; } } - float mgmVecTot[3] = {0.0, 0.0, 0.0}; + double mgmVecTot[3] = {0.0, 0.0, 0.0}; for (uint8_t i = 0; i < 3; i++) { mgmVecTot[i] = sensorFusionNumerator[i] / sensorFusionDenominator[i]; } //-----------------------Mgm Rate Computation --------------------------------------------------- - float mgmVecTotDerivative[3] = {0.0, 0.0, 0.0}; + double mgmVecTotDerivative[3] = {0.0, 0.0, 0.0}; bool mgmVecTotDerivativeValid = false; double timeDiff = timevalOperations::toDouble(timeOfMgmMeasurement - timeOfSavedMagFieldEst); if (timeOfSavedMagFieldEst.tv_sec != 0) { @@ -367,7 +367,7 @@ void SensorProcessing::processSus( sus4VecBody[2], sus5VecBody[2], sus6VecBody[2], sus7VecBody[2], sus8VecBody[2], sus9VecBody[2], sus10VecBody[2], sus11VecBody[2]}}; - float susMeanValue[3] = {0, 0, 0}; + double susMeanValue[3] = {0, 0, 0}; for (uint8_t i = 0; i < 12; i++) { if (validIds[i]) { susMeanValue[0] += susVecBody[0][i]; @@ -375,12 +375,12 @@ void SensorProcessing::processSus( susMeanValue[2] += susVecBody[2][i]; } } - float susVecTot[3] = {0.0, 0.0, 0.0}; - VectorOperations::normalize(susMeanValue, susVecTot, 3); + double susVecTot[3] = {0.0, 0.0, 0.0}; + VectorOperations::normalize(susMeanValue, susVecTot, 3); /* -------- Sun Derivatiative --------------------- */ - float susVecTotDerivative[3] = {0.0, 0.0, 0.0}; + double susVecTotDerivative[3] = {0.0, 0.0, 0.0}; bool susVecTotDerivativeValid = false; double timeDiff = timevalOperations::toDouble(timeOfSusMeasurement - timeOfSavedSusDirEst); if (timeOfSavedSusDirEst.tv_sec != 0) { @@ -438,10 +438,10 @@ void SensorProcessing::processSus( susDataProcessed->sus10vec.setValid(sus10valid); std::memcpy(susDataProcessed->sus11vec.value, sus11VecBody, 3 * sizeof(float)); susDataProcessed->sus11vec.setValid(sus11valid); - std::memcpy(susDataProcessed->susVecTot.value, susVecTot, 3 * sizeof(float)); + std::memcpy(susDataProcessed->susVecTot.value, susVecTot, 3 * sizeof(double)); susDataProcessed->susVecTot.setValid(true); std::memcpy(susDataProcessed->susVecTotDerivative.value, susVecTotDerivative, - 3 * sizeof(float)); + 3 * sizeof(double)); susDataProcessed->susVecTotDerivative.setValid(susVecTotDerivativeValid); std::memcpy(susDataProcessed->sunIjkModel.value, sunIjkModel, 3 * sizeof(double)); susDataProcessed->sunIjkModel.setValid(true); @@ -538,9 +538,13 @@ void SensorProcessing::processGyr( std::memcpy(gyrDataProcessed->gyr0vec.value, gyr0ValueBody, 3 * sizeof(double)); gyrDataProcessed->gyr0vec.setValid(gyr0valid); std::memcpy(gyrDataProcessed->gyr1vec.value, gyr1ValueBody, 3 * sizeof(double)); + gyrDataProcessed->gyr1vec.setValid(gyr1valid); std::memcpy(gyrDataProcessed->gyr2vec.value, gyr2ValueBody, 3 * sizeof(double)); + gyrDataProcessed->gyr2vec.setValid(gyr2valid); std::memcpy(gyrDataProcessed->gyr3vec.value, gyr3ValueBody, 3 * sizeof(double)); + gyrDataProcessed->gyr3vec.setValid(gyr3valid); std::memcpy(gyrDataProcessed->gyrVecTot.value, gyrVecTot, 3 * sizeof(double)); + gyrDataProcessed->gyrVecTot.setValid(true); gyrDataProcessed->setValidity(true, false); } } @@ -582,7 +586,9 @@ void SensorProcessing::process(timeval now, ACS::SensorValues *sensorValues, const AcsParameters *acsParameters) { sensorValues->update(); processGps(sensorValues->gpsSet.latitude.value, sensorValues->gpsSet.longitude.value, - sensorValues->gpsSet.isValid(), gpsDataProcessed); + (sensorValues->gpsSet.latitude.isValid() && sensorValues->gpsSet.longitude.isValid() && + sensorValues->gpsSet.altitude.isValid()), + gpsDataProcessed); processMgm(sensorValues->mgm0Lis3Set.fieldStrengths.value, sensorValues->mgm0Lis3Set.fieldStrengths.isValid(), @@ -594,7 +600,10 @@ void SensorProcessing::process(timeval now, ACS::SensorValues *sensorValues, sensorValues->mgm3Rm3100Set.fieldStrengths.isValid(), sensorValues->imtqMgmSet.mtmRawNt.value, sensorValues->imtqMgmSet.mtmRawNt.isValid(), now, &acsParameters->mgmHandlingParameters, gpsDataProcessed, - sensorValues->gpsSet.altitude.value, sensorValues->gpsSet.isValid(), mgmDataProcessed); + sensorValues->gpsSet.altitude.value, + (sensorValues->gpsSet.latitude.isValid() && sensorValues->gpsSet.longitude.isValid() && + sensorValues->gpsSet.altitude.isValid()), + mgmDataProcessed); processSus(sensorValues->susSets[0].channels.value, sensorValues->susSets[0].channels.isValid(), sensorValues->susSets[1].channels.value, sensorValues->susSets[1].channels.isValid(), -- 2.34.1 From 902caa39850f47c7b70f16046d1b664c43359075 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 17 Nov 2022 16:08:44 +0100 Subject: [PATCH 087/101] double length fixes --- mission/controller/acs/SensorProcessing.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/mission/controller/acs/SensorProcessing.cpp b/mission/controller/acs/SensorProcessing.cpp index 407ba900..4635e673 100644 --- a/mission/controller/acs/SensorProcessing.cpp +++ b/mission/controller/acs/SensorProcessing.cpp @@ -158,10 +158,10 @@ void SensorProcessing::processMgm(const float *mgm0Value, bool mgm0valid, const mgmDataProcessed->mgm3vec.setValid(mgm3valid); std::memcpy(mgmDataProcessed->mgm4vec.value, mgm4ValueBody, 3 * sizeof(float)); mgmDataProcessed->mgm4vec.setValid(mgm4valid); - std::memcpy(mgmDataProcessed->mgmVecTot.value, mgmVecTot, 3 * sizeof(float)); + std::memcpy(mgmDataProcessed->mgmVecTot.value, mgmVecTot, 3 * sizeof(double)); mgmDataProcessed->mgmVecTot.setValid(true); std::memcpy(mgmDataProcessed->mgmVecTotDerivative.value, mgmVecTotDerivative, - 3 * sizeof(float)); + 3 * sizeof(double)); mgmDataProcessed->mgmVecTotDerivative.setValid(mgmVecTotDerivativeValid); std::memcpy(mgmDataProcessed->magIgrfModel.value, magIgrfModel, 3 * sizeof(double)); mgmDataProcessed->magIgrfModel.setValid(gpsValid); -- 2.34.1 From f07b905df54dd138a3cb654b48f5803d40bab82f Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Fri, 18 Nov 2022 10:49:38 +0100 Subject: [PATCH 088/101] corrected output direction of sunVectors --- mission/controller/acs/SusConverter.cpp | 10 +++++----- mission/controller/acs/SusConverter.h | 2 +- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/mission/controller/acs/SusConverter.cpp b/mission/controller/acs/SusConverter.cpp index 26804f12..1dc3a2e2 100644 --- a/mission/controller/acs/SusConverter.cpp +++ b/mission/controller/acs/SusConverter.cpp @@ -107,17 +107,17 @@ void SusConverter::calibration(const float coeffAlpha[9][10], const float coeffB float* SusConverter::calculateSunVector() { // Calculate the normalized Sun Vector - sunVectorBodyFrame[0] = (tan(alphaBetaCalibrated[0] * (M_PI / 180)) / + sunVectorSensorFrame[0] = -(tan(alphaBetaCalibrated[0] * (M_PI / 180)) / (sqrt((powf(tan(alphaBetaCalibrated[0] * (M_PI / 180)), 2)) + powf(tan((alphaBetaCalibrated[1] * (M_PI / 180))), 2) + (1)))); - sunVectorBodyFrame[1] = (tan(alphaBetaCalibrated[1] * (M_PI / 180)) / + sunVectorSensorFrame[1] = -(tan(alphaBetaCalibrated[1] * (M_PI / 180)) / (sqrt(powf((tan(alphaBetaCalibrated[0] * (M_PI / 180))), 2) + powf(tan((alphaBetaCalibrated[1] * (M_PI / 180))), 2) + (1)))); - sunVectorBodyFrame[2] = - (-1 / (sqrt(powf((tan(alphaBetaCalibrated[0] * (M_PI / 180))), 2) + + sunVectorSensorFrame[2] = + -(-1 / (sqrt(powf((tan(alphaBetaCalibrated[0] * (M_PI / 180))), 2) + powf((tan(alphaBetaCalibrated[1] * (M_PI / 180))), 2) + (1)))); - return sunVectorBodyFrame; + return sunVectorSensorFrame; } float* SusConverter::getSunVectorSensorFrame(const uint16_t susChannel[6], diff --git a/mission/controller/acs/SusConverter.h b/mission/controller/acs/SusConverter.h index 01143a39..10079e90 100644 --- a/mission/controller/acs/SusConverter.h +++ b/mission/controller/acs/SusConverter.h @@ -31,7 +31,7 @@ class SusConverter { // float coeffAlpha[9][10]; // float coeffBeta[9][10]; float alphaBetaCalibrated[2]; //[°] - float sunVectorBodyFrame[3]; //[-] + float sunVectorSensorFrame[3]; //[-] bool validFlag[12] = {returnvalue::OK, returnvalue::OK, returnvalue::OK, returnvalue::OK, returnvalue::OK, returnvalue::OK, returnvalue::OK, returnvalue::OK, -- 2.34.1 From 13fe25ff031e9d96c5e5d0989c87662b75c3457e Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Mon, 21 Nov 2022 10:30:48 +0100 Subject: [PATCH 089/101] added dataPool Output, in case MEKF inverion fails --- mission/controller/acs/MultiplicativeKalmanFilter.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.cpp b/mission/controller/acs/MultiplicativeKalmanFilter.cpp index cc136f61..5d66bd8d 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.cpp +++ b/mission/controller/acs/MultiplicativeKalmanFilter.cpp @@ -893,6 +893,16 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst( int inversionFailed = CholeskyDecomposition::invertCholesky(*residualCov, *invResidualCov, invResidualCov1, MDF); if (inversionFailed) { + { + PoolReadGuard pg(mekfData); + if (pg.getReadResult() == returnvalue::OK) { + double unitQuat[4] = {0.0, 0.0, 0.0, 1.0}; + double zeroVec[3] = {0.0, 0.0, 0.0}; + std::memcpy(mekfData->quatMekf.value, unitQuat, 4 * sizeof(double)); + std::memcpy(mekfData->satRotRateMekf.value, zeroVec, 3 * sizeof(double)); + mekfData->setValidity(false, true); + } + } validMekf = false; return KALMAN_INVERSION_FAILED; // RETURN VALUE ? -- Like: Kalman Inversion Failed } -- 2.34.1 From 2d939a289407a1a0e870b06e4543d1f1718f1c70 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 30 Nov 2022 10:35:30 +0100 Subject: [PATCH 090/101] update --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 603b7e85..4cfd2d68 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 603b7e8574d74ba60692115133cde3cd8b8bd423 +Subproject commit 4cfd2d684a531b66ff1b366ef87ac086ba993a96 -- 2.34.1 From b2e0ef24f3825bdd03e1739c93d3fd1444423379 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Tue, 29 Nov 2022 11:45:58 +0100 Subject: [PATCH 091/101] first version for gauss-jordan matrix inversion --- mission/controller/acs/util/MathOperations.h | 577 +++++++++++-------- 1 file changed, 323 insertions(+), 254 deletions(-) diff --git a/mission/controller/acs/util/MathOperations.h b/mission/controller/acs/util/MathOperations.h index 6a534880..c37dbde8 100644 --- a/mission/controller/acs/util/MathOperations.h +++ b/mission/controller/acs/util/MathOperations.h @@ -1,298 +1,367 @@ -/* - * MathOperations.h - * - * Created on: 3 Mar 2022 - * Author: rooob - */ - #ifndef MATH_MATHOPERATIONS_H_ #define MATH_MATHOPERATIONS_H_ -#include -#include -#include -#include #include #include +#include +#include +#include +#include + +#include using namespace Math; -template +template class MathOperations { -public: - static void skewMatrix(const T1 vector[], T2 *result) { - // Input Dimension [3], Output [3][3] - result[0] = 0; - result[1] = -vector[2]; - result[2] = vector[1]; - result[3] = vector[2]; - result[4] = 0; - result[5] = -vector[0]; - result[6] = -vector[1]; - result[7] = vector[0]; - result[8] = 0; - } - static void vecTransposeVecMatrix(const T1 vector1[], const T1 transposeVector2[], - T2 *result, uint8_t size = 3) { - // Looks like MatrixOpertions::multiply is able to do the same thing - for (uint8_t resultColumn = 0; resultColumn < size; resultColumn++) { - for (uint8_t resultRow = 0; resultRow < size; resultRow++) { - result[resultColumn + size * resultRow] = vector1[resultRow] - * transposeVector2[resultColumn]; + public: + static void skewMatrix(const T1 vector[], T2 *result) { + // Input Dimension [3], Output [3][3] + result[0] = 0; + result[1] = -vector[2]; + result[2] = vector[1]; + result[3] = vector[2]; + result[4] = 0; + result[5] = -vector[0]; + result[6] = -vector[1]; + result[7] = vector[0]; + result[8] = 0; + } + static void vecTransposeVecMatrix(const T1 vector1[], const T1 transposeVector2[], T2 *result, + uint8_t size = 3) { + // Looks like MatrixOpertions::multiply is able to do the same thing + for (uint8_t resultColumn = 0; resultColumn < size; resultColumn++) { + for (uint8_t resultRow = 0; resultRow < size; resultRow++) { + result[resultColumn + size * resultRow] = + vector1[resultRow] * transposeVector2[resultColumn]; + } + } + /*matrixSun[i][j] = sunEstB[i] * sunEstB[j]; + matrixMag[i][j] = magEstB[i] * magEstB[j]; + matrixSunMag[i][j] = sunEstB[i] * magEstB[j]; + matrixMagSun[i][j] = magEstB[i] * sunEstB[j];*/ + } - } - } - /*matrixSun[i][j] = sunEstB[i] * sunEstB[j]; - matrixMag[i][j] = magEstB[i] * magEstB[j]; - matrixSunMag[i][j] = sunEstB[i] * magEstB[j]; - matrixMagSun[i][j] = magEstB[i] * sunEstB[j];*/ - } + static void selectionSort(const T1 *matrix, T1 *result, uint8_t rowSize, uint8_t colSize) { + int min_idx; + T1 temp; + memcpy(result, matrix, rowSize * colSize * sizeof(*result)); + // One by one move boundary of unsorted subarray + for (int k = 0; k < rowSize; k++) { + for (int i = 0; i < colSize - 1; i++) { + // Find the minimum element in unsorted array + min_idx = i; + for (int j = i + 1; j < colSize; j++) { + if (result[j + k * colSize] < result[min_idx + k * colSize]) { + min_idx = j; + } + } + // Swap the found minimum element with the first element + temp = result[i + k * colSize]; + result[i + k * colSize] = result[min_idx + k * colSize]; + result[min_idx + k * colSize] = temp; + } + } + } - static void selectionSort(const T1 *matrix, T1 *result, uint8_t rowSize, - uint8_t colSize) { - int min_idx; - T1 temp; - memcpy(result, matrix, rowSize * colSize * sizeof(*result)); - // One by one move boundary of unsorted subarray - for (int k = 0; k < rowSize; k++) { - for (int i = 0; i < colSize - 1; i++) { - // Find the minimum element in unsorted array - min_idx = i; - for (int j = i + 1; j < colSize; j++) { - if (result[j + k * colSize] - < result[min_idx + k * colSize]) { - min_idx = j; - } - } - // Swap the found minimum element with the first element - temp = result[i + k * colSize]; - result[i + k * colSize] = result[min_idx + k * colSize]; - result[min_idx + k * colSize] = temp; - } - } - } + static void convertDateToJD2000(const T1 time, T2 julianDate) { + // time = { Y, M, D, h, m,s} + // time in sec and microsec -> The Epoch (unixtime) + julianDate = 1721013.5 + 367 * time[0] - floor(7 / 4 * (time[0] + (time[1] + 9) / 12)) + + floor(275 * time[1] / 9) + time[2] + + (60 * time[3] + time[4] + (time(5) / 60)) / 1440; + } - static void convertDateToJD2000(const T1 time, T2 julianDate){ + static T1 convertUnixToJD2000(timeval time) { + // time = {{s},{us}} + T1 julianDate2000; + julianDate2000 = (time.tv_sec / 86400.0) + 2440587.5 - 2451545; + return julianDate2000; + } - // time = { Y, M, D, h, m,s} - // time in sec and microsec -> The Epoch (unixtime) - julianDate = 1721013.5 + 367*time[0]- floor(7/4*(time[0]+(time[1]+9)/12)) - +floor(275*time[1]/9)+time[2]+(60*time[3]+time[4]+(time(5)/60))/1440; - } + static void dcmFromQuat(const T1 vector[], T1 *outputDcm) { + // convention q = [qx,qy,qz, qw] + outputDcm[0] = pow(vector[0], 2) - pow(vector[1], 2) - pow(vector[2], 2) + pow(vector[3], 2); + outputDcm[1] = 2 * (vector[0] * vector[1] + vector[2] * vector[3]); + outputDcm[2] = 2 * (vector[0] * vector[2] - vector[1] * vector[3]); - static T1 convertUnixToJD2000(timeval time){ - //time = {{s},{us}} - T1 julianDate2000; - julianDate2000 = (time.tv_sec/86400.0)+2440587.5-2451545; - return julianDate2000; - } + outputDcm[3] = 2 * (vector[1] * vector[0] - vector[2] * vector[3]); + outputDcm[4] = -pow(vector[0], 2) + pow(vector[1], 2) - pow(vector[2], 2) + pow(vector[3], 2); + outputDcm[5] = 2 * (vector[1] * vector[2] + vector[0] * vector[3]); - static void dcmFromQuat(const T1 vector[], T1 *outputDcm){ - // convention q = [qx,qy,qz, qw] - outputDcm[0] = pow(vector[0],2) - pow(vector[1],2) - pow(vector[2],2) + pow(vector[3],2); - outputDcm[1] = 2*(vector[0]*vector[1] + vector[2]*vector[3]); - outputDcm[2] = 2*(vector[0]*vector[2] - vector[1]*vector[3]); + outputDcm[6] = 2 * (vector[2] * vector[0] + vector[1] * vector[3]); + outputDcm[7] = 2 * (vector[2] * vector[1] - vector[0] * vector[3]); + outputDcm[8] = -pow(vector[0], 2) - pow(vector[1], 2) + pow(vector[2], 2) + pow(vector[3], 2); + } - outputDcm[3] = 2*(vector[1]*vector[0] - vector[2]*vector[3]); - outputDcm[4] = -pow(vector[0],2) + pow(vector[1],2) - pow(vector[2],2) + pow(vector[3],2); - outputDcm[5] = 2*(vector[1]*vector[2] + vector[0]*vector[3]); + static void cartesianFromLatLongAlt(const T1 lat, const T1 longi, const T1 alt, + T2 *cartesianOutput) { + double radiusPolar = 6378137; + double radiusEqua = 6356752.314; - outputDcm[6] = 2*(vector[2]*vector[0] + vector[1]*vector[3]); - outputDcm[7] = 2*(vector[2]*vector[1] - vector[0]*vector[3]); - outputDcm[8] = -pow(vector[0],2) - pow(vector[1],2) + pow(vector[2],2) + pow(vector[3],2); + double eccentricity = sqrt(1 - pow(radiusPolar, 2) / pow(radiusEqua, 2)); + double auxRadius = radiusEqua / sqrt(1 - pow(eccentricity, 2) * pow(sin(lat), 2)); - } + cartesianOutput[0] = (auxRadius + alt) * cos(lat) * cos(longi); + cartesianOutput[1] = (auxRadius + alt) * cos(lat) * sin(longi); + cartesianOutput[2] = ((1 - pow(eccentricity, 2)) * auxRadius + alt) * sin(lat); + } - static void cartesianFromLatLongAlt(const T1 lat, const T1 longi, const T1 alt, T2 *cartesianOutput){ + /* @brief: dcmEJ() - calculates the transformation matrix between ECEF and ECI frame + * @param: time Current time + * outputDcmEJ Transformation matrix from ECI (J) to ECEF (E) [3][3] + * @source: Fundamentals of Spacecraft Attitude Determination and Control, P.32ff + * Landis Markley and John L. Crassidis*/ + static void dcmEJ(timeval time, T1 *outputDcmEJ) { + double JD2000Floor = 0; + double JD2000 = convertUnixToJD2000(time); + // Getting Julian Century from Day start : JD (Y,M,D,0,0,0) + JD2000Floor = floor(JD2000); + if ((JD2000 - JD2000Floor) < 0.5) { + JD2000Floor -= 0.5; + } else { + JD2000Floor += 0.5; + } - double radiusPolar = 6378137; - double radiusEqua = 6356752.314; + double JC2000 = JD2000Floor / 36525; + double sec = (JD2000 - JD2000Floor) * 86400; + double gmst = 0; // greenwich mean sidereal time + gmst = 24110.54841 + 8640184.812866 * JC2000 + 0.093104 * pow(JC2000, 2) - + 0.0000062 * pow(JC2000, 3) + 1.002737909350795 * sec; + double rest = gmst / 86400; + double FloorRest = floor(rest); + double secOfDay = rest - FloorRest; + secOfDay *= 86400; + gmst = secOfDay / 240 * PI / 180; - double eccentricity = sqrt(1 - pow(radiusPolar,2) / pow(radiusEqua,2)); - double auxRadius = radiusEqua / sqrt(1 - pow(eccentricity,2) * pow(sin(lat),2)); + outputDcmEJ[0] = cos(gmst); + outputDcmEJ[1] = sin(gmst); + outputDcmEJ[2] = 0; + outputDcmEJ[3] = -sin(gmst); + outputDcmEJ[4] = cos(gmst); + outputDcmEJ[5] = 0; + outputDcmEJ[6] = 0; + outputDcmEJ[7] = 0; + outputDcmEJ[8] = 1; + } - cartesianOutput[0] = (auxRadius + alt) * cos(lat) * cos(longi); - cartesianOutput[1] = (auxRadius + alt) * cos(lat) * sin(longi); - cartesianOutput[2] = ((1 - pow(eccentricity,2)) * auxRadius + alt) * sin(lat); + /* @brief: ecfToEciWithNutPre() - calculates the transformation matrix between ECEF and ECI frame + * give also the back the derivative of this matrix + * @param: unixTime Current time in Unix format + * outputDcmEJ Transformation matrix from ECI (J) to ECEF (E) [3][3] + * outputDotDcmEJ Derivative of transformation matrix [3][3] + * @source: Entwicklung einer Simulationsumgebung und robuster Algorithmen für das Lage- und + Orbitkontrollsystem der Kleinsatelliten Flying Laptop und PERSEUS, P.244ff + * Oliver Zeile + * + https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_Studenten/Marquardt_Robin&openfile=896110*/ + static void ecfToEciWithNutPre(timeval unixTime, T1 *outputDcmEJ, T1 *outputDotDcmEJ) { + // TT = UTC/Unix + 32.184s (TAI Difference) + 27 (Leap Seconds in UTC since 1972) + 10 + //(initial Offset) International Atomic Time (TAI) - } + double JD2000UTC1 = convertUnixToJD2000(unixTime); - /* @brief: dcmEJ() - calculates the transformation matrix between ECEF and ECI frame - * @param: time Current time - * outputDcmEJ Transformation matrix from ECI (J) to ECEF (E) [3][3] - * @source: Fundamentals of Spacecraft Attitude Determination and Control, P.32ff - * Landis Markley and John L. Crassidis*/ - static void dcmEJ(timeval time, T1 * outputDcmEJ){ + // Julian Date / century from TT + timeval terestrialTime = unixTime; + terestrialTime.tv_sec = unixTime.tv_sec + 32.184 + 37; + double JD2000TT = convertUnixToJD2000(terestrialTime); + double JC2000TT = JD2000TT / 36525; - double JD2000Floor = 0; - double JD2000 = convertUnixToJD2000(time); - // Getting Julian Century from Day start : JD (Y,M,D,0,0,0) - JD2000Floor = floor(JD2000); - if ( ( JD2000 - JD2000Floor) < 0.5) { - JD2000Floor -= 0.5; - } - else { - JD2000Floor += 0.5; - } + //------------------------------------------------------------------------------------- + // Calculation of Transformation from earth rotation Theta + //------------------------------------------------------------------------------------- + double theta[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + // Earth Rotation angle + double era = 0; + era = 2 * PI * (0.779057273264 + 1.00273781191135448 * JD2000UTC1); + // Greenwich Mean Sidereal Time + double gmst2000 = 0.014506 + 4612.15739966 * JC2000TT + 1.39667721 * pow(JC2000TT, 2) - + 0.00009344 * pow(JC2000TT, 3) + 0.00001882 * pow(JC2000TT, 4); + double arcsecFactor = 1 * PI / (180 * 3600); + gmst2000 *= arcsecFactor; + gmst2000 += era; - double JC2000 = JD2000Floor / 36525; - double sec = (JD2000 - JD2000Floor) * 86400; - double gmst = 0; //greenwich mean sidereal time - gmst = 24110.54841 + 8640184.812866 * JC2000 + 0.093104 * pow(JC2000,2) - - 0.0000062 * pow(JC2000,3) + 1.002737909350795 * sec; - double rest = gmst / 86400; - double FloorRest = floor(rest); - double secOfDay = rest-FloorRest; - secOfDay *= 86400; - gmst = secOfDay / 240 * PI / 180; + theta[0][0] = cos(gmst2000); + theta[0][1] = sin(gmst2000); + theta[0][2] = 0; + theta[1][0] = -sin(gmst2000); + theta[1][1] = cos(gmst2000); + theta[1][2] = 0; + theta[2][0] = 0; + theta[2][1] = 0; + theta[2][2] = 1; - outputDcmEJ[0] = cos(gmst); - outputDcmEJ[1] = sin(gmst); - outputDcmEJ[2] = 0; - outputDcmEJ[3] = -sin(gmst); - outputDcmEJ[4] = cos(gmst); - outputDcmEJ[5] = 0; - outputDcmEJ[6] = 0; - outputDcmEJ[7] = 0; - outputDcmEJ[8] = 1; + //------------------------------------------------------------------------------------- + // Calculation of Transformation from earth Precession P + //------------------------------------------------------------------------------------- + double precession[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - } + double zeta = 2306.2181 * JC2000TT + 0.30188 * pow(JC2000TT, 2) + 0.017998 * pow(JC2000TT, 3); + double theta2 = 2004.3109 * JC2000TT - 0.42665 * pow(JC2000TT, 2) - 0.041833 * pow(JC2000TT, 3); + double ze = zeta + 0.79280 * pow(JC2000TT, 2) + 0.000205 * pow(JC2000TT, 3); - /* @brief: ecfToEciWithNutPre() - calculates the transformation matrix between ECEF and ECI frame - * give also the back the derivative of this matrix - * @param: unixTime Current time in Unix format - * outputDcmEJ Transformation matrix from ECI (J) to ECEF (E) [3][3] - * outputDotDcmEJ Derivative of transformation matrix [3][3] - * @source: Entwicklung einer Simulationsumgebung und robuster Algorithmen für das Lage- und - Orbitkontrollsystem der Kleinsatelliten Flying Laptop und PERSEUS, P.244ff - * Oliver Zeile - * https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_Studenten/Marquardt_Robin&openfile=896110*/ - static void ecfToEciWithNutPre(timeval unixTime, T1 * outputDcmEJ, T1 * outputDotDcmEJ ) { + zeta *= arcsecFactor; + theta2 *= arcsecFactor; + ze *= arcsecFactor; -// TT = UTC/Unix + 32.184s (TAI Difference) + 27 (Leap Seconds in UTC since 1972) + 10 (initial Offset) -// International Atomic Time (TAI) + precession[0][0] = -sin(ze) * sin(zeta) + cos(ze) * cos(theta2) * cos(zeta); + precession[1][0] = cos(ze) * sin(zeta) + sin(ze) * cos(theta2) * cos(zeta); + precession[2][0] = sin(theta2) * cos(zeta); + precession[0][1] = -sin(ze) * cos(zeta) - cos(ze) * cos(theta2) * sin(zeta); + precession[1][1] = cos(ze) * cos(zeta) - sin(ze) * cos(theta2) * sin(zeta); + precession[2][1] = -sin(theta2) * sin(zeta); + precession[0][2] = -cos(ze) * sin(theta2); + precession[1][2] = -sin(ze) * sin(theta2); + precession[2][2] = cos(theta2); - double JD2000UTC1 = convertUnixToJD2000(unixTime); + //------------------------------------------------------------------------------------- + // Calculation of Transformation from earth Nutation size + //------------------------------------------------------------------------------------- + double nutation[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + // lunar asc node + double Om = 125 * 3600 + 2 * 60 + 40.28 - (1934 * 3600 + 8 * 60 + 10.539) * JC2000TT + + 7.455 * pow(JC2000TT, 2) + 0.008 * pow(JC2000TT, 3); + Om *= arcsecFactor; + // delta psi approx + double dp = -17.2 * arcsecFactor * sin(Om); -// Julian Date / century from TT - timeval terestrialTime = unixTime; - terestrialTime.tv_sec = unixTime.tv_sec + 32.184 + 37; - double JD2000TT = convertUnixToJD2000(terestrialTime); - double JC2000TT = JD2000TT / 36525; + // delta eps approx + double de = 9.203 * arcsecFactor * cos(Om); -//------------------------------------------------------------------------------------- -// Calculation of Transformation from earth rotation Theta -//------------------------------------------------------------------------------------- - double theta[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; -// Earth Rotation angle - double era = 0; - era = 2* PI *(0.779057273264 + 1.00273781191135448 * JD2000UTC1); -// Greenwich Mean Sidereal Time - double gmst2000 = 0.014506 + 4612.15739966 * JC2000TT + 1.39667721 * pow(JC2000TT,2) - - 0.00009344 * pow(JC2000TT,3) + 0.00001882 * pow(JC2000TT,4); - double arcsecFactor = 1 * PI / (180 * 3600); - gmst2000 *= arcsecFactor; - gmst2000 += era; + // % true obliquity of the ecliptic eps p.71 (simplified) + double e = 23.43929111 * PI / 180 - 46.8150 / 3600 * JC2000TT * PI / 180; + ; - theta[0][0] = cos(gmst2000); - theta[0][1] = sin(gmst2000); - theta[0][2] = 0; - theta[1][0] = -sin(gmst2000); - theta[1][1] = cos(gmst2000); - theta[1][2] = 0; - theta[2][0] = 0; - theta[2][1] = 0; - theta[2][2] = 1; + nutation[0][0] = cos(dp); + nutation[1][0] = cos(e + de) * sin(dp); + nutation[2][0] = sin(e + de) * sin(dp); + nutation[0][1] = -cos(e) * sin(dp); + nutation[1][1] = cos(e) * cos(e + de) * cos(dp) + sin(e) * sin(e + de); + nutation[2][1] = cos(e) * sin(e + de) * cos(dp) - sin(e) * cos(e + de); + nutation[0][2] = -sin(e) * sin(dp); + nutation[1][2] = sin(e) * cos(e + de) * cos(dp) - cos(e) * sin(e + de); + nutation[2][2] = sin(e) * sin(e + de) * cos(dp) + cos(e) * cos(e + de); -//------------------------------------------------------------------------------------- -// Calculation of Transformation from earth Precession P -//------------------------------------------------------------------------------------- - double precession[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; + //------------------------------------------------------------------------------------- + // Calculation of Derivative of rotation matrix from earth + //------------------------------------------------------------------------------------- + double thetaDot[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double dotMatrix[3][3] = {{0, 1, 0}, {-1, 0, 0}, {0, 0, 0}}; + double omegaEarth = 0.000072921158553; + MatrixOperations::multiply(*dotMatrix, *theta, *thetaDot, 3, 3, 3); + MatrixOperations::multiplyScalar(*thetaDot, omegaEarth, *thetaDot, 3, 3); - double zeta = 2306.2181 * JC2000TT + 0.30188 * pow(JC2000TT,2) + 0.017998 * pow(JC2000TT,3); - double theta2 = 2004.3109 * JC2000TT - 0.42665 * pow(JC2000TT,2) - 0.041833 * pow(JC2000TT,3); - double ze = zeta + 0.79280 * pow(JC2000TT,2) + 0.000205 * pow(JC2000TT,3); + //------------------------------------------------------------------------------------- + // Calculation of transformation matrix and Derivative of transformation matrix + //------------------------------------------------------------------------------------- + double nutationPrecession[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MatrixOperations::multiply(*nutation, *precession, *nutationPrecession, 3, 3, 3); + MatrixOperations::multiply(*nutationPrecession, *theta, outputDcmEJ, 3, 3, 3); - zeta *= arcsecFactor; - theta2 *= arcsecFactor; - ze *= arcsecFactor; + MatrixOperations::multiply(*nutationPrecession, *thetaDot, outputDotDcmEJ, 3, 3, 3); + } - precession[0][0]=-sin(ze)*sin(zeta)+cos(ze)*cos(theta2)*cos(zeta); - precession[1][0]=cos(ze)*sin(zeta)+sin(ze)*cos(theta2)*cos(zeta); - precession[2][0]=sin(theta2)*cos(zeta); - precession[0][1]=-sin(ze)*cos(zeta)-cos(ze)*cos(theta2)*sin(zeta); - precession[1][1]=cos(ze)*cos(zeta)-sin(ze)*cos(theta2)*sin(zeta); - precession[2][1]=-sin(theta2)*sin(zeta); - precession[0][2]=-cos(ze)*sin(theta2); - precession[1][2]=-sin(ze)*sin(theta2); - precession[2][2]=cos(theta2); + static void inverseMatrixDimThree(const T1 *matrix, T1 *output) { + int i, j; + double determinant; + double mat[3][3] = {{matrix[0], matrix[1], matrix[2]}, + {matrix[3], matrix[4], matrix[5]}, + {matrix[6], matrix[7], matrix[8]}}; -//------------------------------------------------------------------------------------- -// Calculation of Transformation from earth Nutation N -//------------------------------------------------------------------------------------- - double nutation[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; -// lunar asc node - double Om = 125 * 3600 + 2 * 60 + 40.28 - (1934 * 3600 + 8 * 60 + 10.539) * JC2000TT + - 7.455 * pow(JC2000TT,2) + 0.008 * pow(JC2000TT,3); - Om *= arcsecFactor; -// delta psi approx - double dp = -17.2 * arcsecFactor *sin(Om); + for (i = 0; i < 3; i++) { + determinant = determinant + (mat[0][i] * (mat[1][(i + 1) % 3] * mat[2][(i + 2) % 3] - + mat[1][(i + 2) % 3] * mat[2][(i + 1) % 3])); + } + // cout<<"\size\ndeterminant: "<::multiply(*dotMatrix, *theta, *thetaDot, 3, 3, 3); - MatrixOperations::multiplyScalar(*thetaDot, omegaEarth, *thetaDot, 3, 3); - -//------------------------------------------------------------------------------------- -// Calculation of transformation matrix and Derivative of transformation matrix -//------------------------------------------------------------------------------------- - double nutationPrecession[3][3] = {{0,0,0},{0,0,0},{0,0,0}}; - MatrixOperations::multiply(*nutation, *precession, *nutationPrecession, 3, 3, 3); - MatrixOperations::multiply(*nutationPrecession, *theta, outputDcmEJ, 3, 3, 3); - - MatrixOperations::multiply(*nutationPrecession, *thetaDot, outputDotDcmEJ, 3, 3, 3); - - } - - static void inverseMatrixDimThree(const T1 *matrix, T1 * output){ - - int i,j; - double determinant; - double mat[3][3] = {{matrix[0], matrix[1], matrix[2]},{matrix[3], matrix[4], matrix[5]}, - {matrix[6], matrix[7], matrix[8]}}; - - for(i = 0; i < 3; i++) { - determinant = determinant + (mat[0][i] * (mat[1][(i+1)%3] * mat[2][(i+2)%3] - mat[1][(i+2)%3] * mat[2][(i+1)%3])); - } -// cout<<"\n\ndeterminant: "<::matrixDeterminant(*submatrix, size - 1)); + } + } + return det; + } + static int inverseMatrix(const T1 *inputMatrix, T1 *inverse, uint8_t size) { + if (MathOperations::matrixDeterminant(*inputMatrix, size) == 0) { + return 0; // Matrix is singular and not invertible + } + T1 matrix[size][size], identity[size][size] = {0}; + // reformat array to matrix + for (uint8_t row = 0; row < size; row++) { + for (uint8_t col = 0; col < size; col++) { + matrix[row][col] = inputMatrix[row * size + col]; + } + } + // init identity matrix + for (uint8_t diag = 0; diag < size; diag++) { + identity[diag][diag] = 1; + } + // gauss-jordan algo + for (uint8_t row = 0; row < size; row++) { + uint8_t rowIndex = row; + // check if diag entry is 0 + // in case it is, find next row whose diag entry is not 0 + while (matrix[rowIndex][row] == 0) { + if (rowIndex < size) { + rowIndex++; + } else { + return 0; // Matrix is not invertible + } + } + // swap rows if needed + if (rowIndex != row) { + for (uint8_t colIndex = 0; colIndex < size; colIndex++) { + std::swap(matrix[row][colIndex], matrix[rowIndex][colIndex]); + std::swap(identity[row][colIndex], identity[rowIndex][colIndex]); + } + } + // normalize line + for (uint8_t colIndex = row; colIndex < size; colIndex++) { + matrix[row][colIndex] = matrix[row][colIndex] / matrix[row][row]; + identity[row][colIndex] = identity[row][colIndex] / matrix[row][row]; + } + // make elements of the same col in following rows to 0 + for (uint8_t rowIndex = row + 1; rowIndex < size; rowIndex++) { + for (uint8_t colIndex = row; colIndex < size; colIndex++) { + matrix[rowIndex][colIndex] -= matrix[row][colIndex] * matrix[rowIndex][row]; + identity[rowIndex][colIndex] -= identity[row][colIndex] * matrix[rowIndex][row]; + } + } + } + std::memcpy(inverse, identity, size * size * sizeof(T1)); + return 1; // successful inversion + } }; #endif /* ACS_MATH_MATHOPERATIONS_H_ */ -- 2.34.1 From b2442041f0c74581c5003e589d7cea68c0eee778 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Wed, 30 Nov 2022 09:07:09 +0100 Subject: [PATCH 092/101] gauss-jordan v2 that hopefully noone ever sees --- .../acs/MultiplicativeKalmanFilter.cpp | 10 ++-- mission/controller/acs/util/MathOperations.h | 53 +++++++++++++++---- 2 files changed, 49 insertions(+), 14 deletions(-) diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.cpp b/mission/controller/acs/MultiplicativeKalmanFilter.cpp index 5d66bd8d..4717dc79 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.cpp +++ b/mission/controller/acs/MultiplicativeKalmanFilter.cpp @@ -888,10 +888,14 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst( // (H * P * H' + R) MatrixOperations::add(*residualCov, *measCovMatrix, *residualCov, MDF, MDF); // <> - double invResidualCov1[MDF] = {0}; + // double invResidualCov1[MDF] = {0}; double invResidualCov[MDF][MDF] = {{0}}; - int inversionFailed = CholeskyDecomposition::invertCholesky(*residualCov, *invResidualCov, - invResidualCov1, MDF); + // int inversionFailed = CholeskyDecomposition::invertCholesky(*residualCov, + // *invResidualCov, + // invResidualCov1, MDF); + int inversionFailed = MathOperations::inverseMatrix(*residualCov, *invResidualCov, MDF); + double test[MDF][MDF]; + MatrixOperations::multiply(*residualCov, *invResidualCov, *test, MDF, MDF, MDF); if (inversionFailed) { { PoolReadGuard pg(mekfData); diff --git a/mission/controller/acs/util/MathOperations.h b/mission/controller/acs/util/MathOperations.h index c37dbde8..8279ec40 100644 --- a/mission/controller/acs/util/MathOperations.h +++ b/mission/controller/acs/util/MathOperations.h @@ -313,10 +313,11 @@ class MathOperations { } static int inverseMatrix(const T1 *inputMatrix, T1 *inverse, uint8_t size) { - if (MathOperations::matrixDeterminant(*inputMatrix, size) == 0) { - return 0; // Matrix is singular and not invertible + std::cout << MathOperations::matrixDeterminant(inputMatrix, size) << std::endl; + if (MathOperations::matrixDeterminant(inputMatrix, size) == 0) { + return 1; // Matrix is singular and not invertible } - T1 matrix[size][size], identity[size][size] = {0}; + T1 matrix[size][size], identity[size][size]; // reformat array to matrix for (uint8_t row = 0; row < size; row++) { for (uint8_t col = 0; col < size; col++) { @@ -324,10 +325,12 @@ class MathOperations { } } // init identity matrix + std::memset(identity, 0.0, sizeof(identity)); for (uint8_t diag = 0; diag < size; diag++) { identity[diag][diag] = 1; } // gauss-jordan algo + // start with gauss for (uint8_t row = 0; row < size; row++) { uint8_t rowIndex = row; // check if diag entry is 0 @@ -336,7 +339,7 @@ class MathOperations { if (rowIndex < size) { rowIndex++; } else { - return 0; // Matrix is not invertible + return 1; // Matrix is not invertible } } // swap rows if needed @@ -347,20 +350,48 @@ class MathOperations { } } // normalize line + double normFactor = matrix[row][row]; for (uint8_t colIndex = row; colIndex < size; colIndex++) { - matrix[row][colIndex] = matrix[row][colIndex] / matrix[row][row]; - identity[row][colIndex] = identity[row][colIndex] / matrix[row][row]; + matrix[row][colIndex] /= normFactor; + identity[row][colIndex] /= normFactor; } // make elements of the same col in following rows to 0 + std::cout << "C++ sucks" << std::endl; for (uint8_t rowIndex = row + 1; rowIndex < size; rowIndex++) { - for (uint8_t colIndex = row; colIndex < size; colIndex++) { - matrix[rowIndex][colIndex] -= matrix[row][colIndex] * matrix[rowIndex][row]; - identity[rowIndex][colIndex] -= identity[row][colIndex] * matrix[rowIndex][row]; + double elimFactor = matrix[rowIndex][row]; + for (uint8_t colIndex = 0; colIndex < size; colIndex++) { + matrix[rowIndex][colIndex] -= matrix[row][colIndex] * elimFactor; + identity[rowIndex][colIndex] -= identity[row][colIndex] * elimFactor; } } } - std::memcpy(inverse, identity, size * size * sizeof(T1)); - return 1; // successful inversion + // finish with jordan + for (uint8_t row = size - 1; row > 0; row--) { + for (int16_t rowIndex = row - 1; rowIndex >= 0; rowIndex--) { + double elimFactor = matrix[rowIndex][row]; + for (uint8_t colIndex = 0; colIndex < size; colIndex++) { + matrix[rowIndex][colIndex] -= matrix[row][colIndex] * elimFactor; + identity[rowIndex][row] -= identity[row][colIndex] * elimFactor; + } + } + } + T1 test[size][size]; + MatrixOperations::multiply(inputMatrix, *identity, *test, size, size, size); + std::cout << "[\n" + << test[0][0] << " " << test[0][1] << " " << test[0][2] << " " << test[0][3] << " " + << test[0][4] << " " << test[0][5] << "\n" + << test[1][0] << " " << test[1][1] << " " << test[1][2] << " " << test[1][3] << " " + << test[1][4] << " " << test[1][5] << "\n" + << test[2][0] << " " << test[2][1] << " " << test[2][2] << " " << test[2][3] << " " + << test[2][4] << " " << test[2][5] << "\n" + << test[3][0] << " " << test[3][1] << " " << test[3][2] << " " << test[3][3] << " " + << test[3][4] << " " << test[3][5] << "\n" + << test[4][0] << " " << test[4][1] << " " << test[4][2] << " " << test[4][3] << " " + << test[4][4] << " " << test[4][5] << "\n" + << test[5][0] << " " << test[5][1] << " " << test[5][2] << " " << test[5][3] << " " + << test[5][4] << " " << test[5][5] << "\n]" << std::endl; + std::memcpy(inverse, identity, sizeof(identity)); + return 0; // successful inversion } }; -- 2.34.1 From ce83b64ca212dc4c624bb82ce1733f1dd0964e1d Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 1 Dec 2022 09:15:42 +0100 Subject: [PATCH 093/101] working versions of inverse calc and determinant calc --- .../acs/MultiplicativeKalmanFilter.cpp | 6 - mission/controller/acs/util/MathOperations.h | 115 +++++++++--------- 2 files changed, 56 insertions(+), 65 deletions(-) diff --git a/mission/controller/acs/MultiplicativeKalmanFilter.cpp b/mission/controller/acs/MultiplicativeKalmanFilter.cpp index 4717dc79..199440d5 100644 --- a/mission/controller/acs/MultiplicativeKalmanFilter.cpp +++ b/mission/controller/acs/MultiplicativeKalmanFilter.cpp @@ -888,14 +888,8 @@ ReturnValue_t MultiplicativeKalmanFilter::mekfEst( // (H * P * H' + R) MatrixOperations::add(*residualCov, *measCovMatrix, *residualCov, MDF, MDF); // <> - // double invResidualCov1[MDF] = {0}; double invResidualCov[MDF][MDF] = {{0}}; - // int inversionFailed = CholeskyDecomposition::invertCholesky(*residualCov, - // *invResidualCov, - // invResidualCov1, MDF); int inversionFailed = MathOperations::inverseMatrix(*residualCov, *invResidualCov, MDF); - double test[MDF][MDF]; - MatrixOperations::multiply(*residualCov, *invResidualCov, *test, MDF, MDF, MDF); if (inversionFailed) { { PoolReadGuard pg(mekfData); diff --git a/mission/controller/acs/util/MathOperations.h b/mission/controller/acs/util/MathOperations.h index 8279ec40..6484a72d 100644 --- a/mission/controller/acs/util/MathOperations.h +++ b/mission/controller/acs/util/MathOperations.h @@ -285,7 +285,7 @@ class MathOperations { static float matrixDeterminant(const T1 *inputMatrix, uint8_t size) { float det = 0; - T1 matrix[size][size], submatrix[size][size]; + T1 matrix[size][size], submatrix[size - 1][size - 1]; for (uint8_t row = 0; row < size; row++) { for (uint8_t col = 0; col < size; col++) { matrix[row][col] = inputMatrix[row * size + col]; @@ -294,26 +294,25 @@ class MathOperations { if (size == 2) return ((matrix[0][0] * matrix[1][1]) - (matrix[1][0] * matrix[0][1])); else { - for (uint8_t x = 0; x < size; x++) { - int subi = 0; - for (uint8_t i = 1; i < size; i++) { - int subj = 0; - for (uint8_t j = 0; j < size; j++) { - if (j == x) continue; - submatrix[subi][subj] = matrix[i][j]; - subj++; + for (uint8_t col = 0; col < size; col++) { + int subRow = 0; + for (uint8_t rowIndex = 1; rowIndex < size; rowIndex++) { + int subCol = 0; + for (uint8_t colIndex = 0; colIndex < size; colIndex++) { + if (colIndex == col) continue; + submatrix[subRow][subCol] = matrix[rowIndex][colIndex]; + subCol++; } - subi++; + subRow++; } - det = det + (pow(-1, x) * matrix[0][x] * - MathOperations::matrixDeterminant(*submatrix, size - 1)); + det += (pow(-1, col) * matrix[0][col] * + MathOperations::matrixDeterminant(*submatrix, size - 1)); } } return det; } static int inverseMatrix(const T1 *inputMatrix, T1 *inverse, uint8_t size) { - std::cout << MathOperations::matrixDeterminant(inputMatrix, size) << std::endl; if (MathOperations::matrixDeterminant(inputMatrix, size) == 0) { return 1; // Matrix is singular and not invertible } @@ -330,66 +329,64 @@ class MathOperations { identity[diag][diag] = 1; } // gauss-jordan algo - // start with gauss + // sort matrix such as no diag entry shall be 0 + // should not be needed as such a matrix has a det=0 for (uint8_t row = 0; row < size; row++) { - uint8_t rowIndex = row; - // check if diag entry is 0 - // in case it is, find next row whose diag entry is not 0 - while (matrix[rowIndex][row] == 0) { - if (rowIndex < size) { + if (matrix[row][row] == 0.0) { + bool swaped = false; + uint8_t rowIndex = 0; + while ((rowIndex < size) && !swaped) { + if ((matrix[rowIndex][row] != 0.0) && (matrix[row][rowIndex] != 0.0)) { + for (uint8_t colIndex = 0; colIndex < size; colIndex++) { + std::swap(matrix[row][colIndex], matrix[rowIndex][colIndex]); + std::swap(identity[row][colIndex], identity[rowIndex][colIndex]); + } + swaped = true; + } rowIndex++; - } else { - return 1; // Matrix is not invertible + } + if (!swaped) { + return 1; // matrix not invertible } } - // swap rows if needed - if (rowIndex != row) { + } + + for (int row = 0; row < size; row++) { + if (matrix[row][row] == 0.0) { + uint8_t rowIndex; + if (row == 0) { + rowIndex = size - 1; + } else { + rowIndex = row - 1; + } for (uint8_t colIndex = 0; colIndex < size; colIndex++) { std::swap(matrix[row][colIndex], matrix[rowIndex][colIndex]); std::swap(identity[row][colIndex], identity[rowIndex][colIndex]); } - } - // normalize line - double normFactor = matrix[row][row]; - for (uint8_t colIndex = row; colIndex < size; colIndex++) { - matrix[row][colIndex] /= normFactor; - identity[row][colIndex] /= normFactor; - } - // make elements of the same col in following rows to 0 - std::cout << "C++ sucks" << std::endl; - for (uint8_t rowIndex = row + 1; rowIndex < size; rowIndex++) { - double elimFactor = matrix[rowIndex][row]; - for (uint8_t colIndex = 0; colIndex < size; colIndex++) { - matrix[rowIndex][colIndex] -= matrix[row][colIndex] * elimFactor; - identity[rowIndex][colIndex] -= identity[row][colIndex] * elimFactor; + row--; + if (row < 0) { + return 1; // Matrix is not invertible } } } - // finish with jordan - for (uint8_t row = size - 1; row > 0; row--) { - for (int16_t rowIndex = row - 1; rowIndex >= 0; rowIndex--) { - double elimFactor = matrix[rowIndex][row]; - for (uint8_t colIndex = 0; colIndex < size; colIndex++) { - matrix[rowIndex][colIndex] -= matrix[row][colIndex] * elimFactor; - identity[rowIndex][row] -= identity[row][colIndex] * elimFactor; + // remove non diag elements in matrix (jordan) + for (int row = 0; row < size; row++) { + for (int rowIndex = 0; rowIndex < size; rowIndex++) { + if (row != rowIndex) { + double ratio = matrix[rowIndex][row] / matrix[row][row]; + for (int colIndex = 0; colIndex < size; colIndex++) { + matrix[rowIndex][colIndex] -= ratio * matrix[row][colIndex]; + identity[rowIndex][colIndex] -= ratio * identity[row][colIndex]; + } } } } - T1 test[size][size]; - MatrixOperations::multiply(inputMatrix, *identity, *test, size, size, size); - std::cout << "[\n" - << test[0][0] << " " << test[0][1] << " " << test[0][2] << " " << test[0][3] << " " - << test[0][4] << " " << test[0][5] << "\n" - << test[1][0] << " " << test[1][1] << " " << test[1][2] << " " << test[1][3] << " " - << test[1][4] << " " << test[1][5] << "\n" - << test[2][0] << " " << test[2][1] << " " << test[2][2] << " " << test[2][3] << " " - << test[2][4] << " " << test[2][5] << "\n" - << test[3][0] << " " << test[3][1] << " " << test[3][2] << " " << test[3][3] << " " - << test[3][4] << " " << test[3][5] << "\n" - << test[4][0] << " " << test[4][1] << " " << test[4][2] << " " << test[4][3] << " " - << test[4][4] << " " << test[4][5] << "\n" - << test[5][0] << " " << test[5][1] << " " << test[5][2] << " " << test[5][3] << " " - << test[5][4] << " " << test[5][5] << "\n]" << std::endl; + // normalize rows in matrix (gauss) + for (int row = 0; row < size; row++) { + for (int col = 0; col < size; col++) { + identity[row][col] = identity[row][col] / matrix[row][row]; + } + } std::memcpy(inverse, identity, sizeof(identity)); return 0; // successful inversion } -- 2.34.1 From 377a672cd204e5319928c888af48a98431f7a8a4 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 1 Dec 2022 13:59:26 +0100 Subject: [PATCH 094/101] detumblecounter init --- mission/controller/acs/AcsParameters.h | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/mission/controller/acs/AcsParameters.h b/mission/controller/acs/AcsParameters.h index 813851dc..828e4495 100644 --- a/mission/controller/acs/AcsParameters.h +++ b/mission/controller/acs/AcsParameters.h @@ -895,9 +895,10 @@ class AcsParameters /*: public HasParametersIF*/ { } magnetorquesParameter; struct DetumbleParameter { - uint8_t detumblecounter; - double omegaDetumbleStart; - double omegaDetumbleEnd; + 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; }; -- 2.34.1 From 08bdc875055eff86a281c43eb8cbb840df6a3a45 Mon Sep 17 00:00:00 2001 From: Marius Eggert Date: Thu, 1 Dec 2022 14:19:42 +0100 Subject: [PATCH 095/101] removed hardcoded modes --- mission/controller/AcsController.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index d00bb816..f9ea5926 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -82,11 +82,6 @@ void AcsController::performControlOperation() { copyGyrData(); } } - - // DEBUG : REMOVE AFTER COMPLETION - mode = MODE_ON; - submode = SUBMODE_SAFE; - // DEBUG END } void AcsController::performSafe() { -- 2.34.1 From a3a919437e9d6d7f8a49de7adba75c4c7951ff54 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Dec 2022 15:56:40 +0100 Subject: [PATCH 096/101] bump submodules --- fsfw | 2 +- tmtc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/fsfw b/fsfw index 672fca51..5b0ea912 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 672fca5169b017387e58e2ff864913d932c59aa1 +Subproject commit 5b0ea91222a6b8efb2f4562cfecbcb735dfeedd5 diff --git a/tmtc b/tmtc index 4cfd2d68..6308bbb3 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 4cfd2d684a531b66ff1b366ef87ac086ba993a96 +Subproject commit 6308bbb3f0e4387508371bd3d18c52f404c4e18b -- 2.34.1 From 828738ba0e46f22666531c224c740c44436cae26 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Dec 2022 15:56:55 +0100 Subject: [PATCH 097/101] afmt --- dummies/GyroL3GD20Dummy.cpp | 1 - dummies/ImtqDummy.cpp | 2 +- dummies/SusDummy.cpp | 8 +- mission/controller/AcsController.h | 2 +- mission/controller/CMakeLists.txt | 2 +- mission/controller/acs/CMakeLists.txt | 18 +- mission/controller/acs/SusConverter.cpp | 10 +- mission/controller/acs/SusConverter.h | 8 +- mission/controller/acs/config/classIds.h | 15 +- mission/controller/acs/control/CMakeLists.txt | 7 +- mission/controller/acs/control/Detumble.cpp | 22 +-- mission/controller/acs/control/Detumble.h | 46 +++-- mission/controller/acs/control/PtgCtrl.cpp | 160 +++++++++--------- .../acs/util/CholeskyDecomposition.h | 156 +++++++++-------- 14 files changed, 217 insertions(+), 240 deletions(-) diff --git a/dummies/GyroL3GD20Dummy.cpp b/dummies/GyroL3GD20Dummy.cpp index a800cd62..20309c63 100644 --- a/dummies/GyroL3GD20Dummy.cpp +++ b/dummies/GyroL3GD20Dummy.cpp @@ -38,7 +38,6 @@ void GyroL3GD20Dummy::fillCommandAndReplyMap() {} uint32_t GyroL3GD20Dummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; } - ReturnValue_t GyroL3GD20Dummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { localDataPoolMap.emplace(L3GD20H::ANG_VELOC_X, new PoolEntry({1.2}, true)); diff --git a/dummies/ImtqDummy.cpp b/dummies/ImtqDummy.cpp index 7f64d977..fdc7b009 100644 --- a/dummies/ImtqDummy.cpp +++ b/dummies/ImtqDummy.cpp @@ -39,7 +39,7 @@ uint32_t ImtqDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { retur ReturnValue_t ImtqDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { localDataPoolMap.emplace(IMTQ::MCU_TEMPERATURE, new PoolEntry({0})); - localDataPoolMap.emplace(IMTQ::MGM_CAL_NT, new PoolEntry({0.0,0.0,0.0})); + localDataPoolMap.emplace(IMTQ::MGM_CAL_NT, new PoolEntry({0.0, 0.0, 0.0})); localDataPoolMap.emplace(IMTQ::ACTUATION_CAL_STATUS, new PoolEntry({0})); localDataPoolMap.emplace(IMTQ::MTM_RAW, new PoolEntry({0.12, 0.76, -0.45}, true)); localDataPoolMap.emplace(IMTQ::ACTUATION_RAW_STATUS, new PoolEntry({0})); diff --git a/dummies/SusDummy.cpp b/dummies/SusDummy.cpp index 28f85969..c0aed6dd 100644 --- a/dummies/SusDummy.cpp +++ b/dummies/SusDummy.cpp @@ -35,9 +35,9 @@ uint32_t SusDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return ReturnValue_t SusDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { - localDataPoolMap.emplace(SUS::SusPoolIds::TEMPERATURE_C, new PoolEntry({0}, 1, true)); - localDataPoolMap.emplace(SUS::SusPoolIds::CHANNEL_VEC, - new PoolEntry({0, 0, 0, 0, 0, 0},true)); + localDataPoolMap.emplace(SUS::SusPoolIds::TEMPERATURE_C, new PoolEntry({0}, 1, true)); + localDataPoolMap.emplace(SUS::SusPoolIds::CHANNEL_VEC, + new PoolEntry({0, 0, 0, 0, 0, 0}, true)); - return returnvalue::OK; + return returnvalue::OK; } diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index ed896d8e..1c4996b3 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -70,7 +70,7 @@ class AcsController : public ExtendedControllerBase { void announceMode(bool recursive); /* ACS Datasets */ -IMTQ::DipoleActuationSet dipoleSet = IMTQ::DipoleActuationSet(objects::IMTQ_HANDLER); + IMTQ::DipoleActuationSet dipoleSet = IMTQ::DipoleActuationSet(objects::IMTQ_HANDLER); // MGMs acsctrl::MgmDataRaw mgmDataRaw; PoolEntry mgm0VecRaw = PoolEntry(3); diff --git a/mission/controller/CMakeLists.txt b/mission/controller/CMakeLists.txt index 463e6a5d..6177a14b 100644 --- a/mission/controller/CMakeLists.txt +++ b/mission/controller/CMakeLists.txt @@ -3,4 +3,4 @@ if(TGT_BSP MATCHES "arm/q7s" OR TGT_BSP MATCHES "") AcsController.cpp) endif() -add_subdirectory(acs) \ No newline at end of file +add_subdirectory(acs) diff --git a/mission/controller/acs/CMakeLists.txt b/mission/controller/acs/CMakeLists.txt index a379197d..3c4a3475 100644 --- a/mission/controller/acs/CMakeLists.txt +++ b/mission/controller/acs/CMakeLists.txt @@ -1,13 +1,13 @@ target_sources( ${LIB_EIVE_MISSION} PRIVATE AcsParameters.cpp - ActuatorCmd.cpp - Guidance.cpp - Igrf13Model.cpp - MultiplicativeKalmanFilter.cpp - Navigation.cpp - SensorProcessing.cpp - SensorValues.cpp - SusConverter.cpp) - + ActuatorCmd.cpp + Guidance.cpp + Igrf13Model.cpp + MultiplicativeKalmanFilter.cpp + Navigation.cpp + SensorProcessing.cpp + SensorValues.cpp + SusConverter.cpp) + add_subdirectory(control) diff --git a/mission/controller/acs/SusConverter.cpp b/mission/controller/acs/SusConverter.cpp index 1dc3a2e2..7020742a 100644 --- a/mission/controller/acs/SusConverter.cpp +++ b/mission/controller/acs/SusConverter.cpp @@ -108,14 +108,14 @@ void SusConverter::calibration(const float coeffAlpha[9][10], const float coeffB float* SusConverter::calculateSunVector() { // Calculate the normalized Sun Vector sunVectorSensorFrame[0] = -(tan(alphaBetaCalibrated[0] * (M_PI / 180)) / - (sqrt((powf(tan(alphaBetaCalibrated[0] * (M_PI / 180)), 2)) + - powf(tan((alphaBetaCalibrated[1] * (M_PI / 180))), 2) + (1)))); + (sqrt((powf(tan(alphaBetaCalibrated[0] * (M_PI / 180)), 2)) + + powf(tan((alphaBetaCalibrated[1] * (M_PI / 180))), 2) + (1)))); sunVectorSensorFrame[1] = -(tan(alphaBetaCalibrated[1] * (M_PI / 180)) / - (sqrt(powf((tan(alphaBetaCalibrated[0] * (M_PI / 180))), 2) + - powf(tan((alphaBetaCalibrated[1] * (M_PI / 180))), 2) + (1)))); + (sqrt(powf((tan(alphaBetaCalibrated[0] * (M_PI / 180))), 2) + + powf(tan((alphaBetaCalibrated[1] * (M_PI / 180))), 2) + (1)))); sunVectorSensorFrame[2] = -(-1 / (sqrt(powf((tan(alphaBetaCalibrated[0] * (M_PI / 180))), 2) + - powf((tan(alphaBetaCalibrated[1] * (M_PI / 180))), 2) + (1)))); + powf((tan(alphaBetaCalibrated[1] * (M_PI / 180))), 2) + (1)))); return sunVectorSensorFrame; } diff --git a/mission/controller/acs/SusConverter.h b/mission/controller/acs/SusConverter.h index 10079e90..b3829827 100644 --- a/mission/controller/acs/SusConverter.h +++ b/mission/controller/acs/SusConverter.h @@ -27,10 +27,10 @@ class SusConverter { const float coeffBeta[9][10]); private: - float alphaBetaRaw[2]; //[°] - // float coeffAlpha[9][10]; - // float coeffBeta[9][10]; - float alphaBetaCalibrated[2]; //[°] + float alphaBetaRaw[2]; //[°] + // float coeffAlpha[9][10]; + // float coeffBeta[9][10]; + float alphaBetaCalibrated[2]; //[°] float sunVectorSensorFrame[3]; //[-] bool validFlag[12] = {returnvalue::OK, returnvalue::OK, returnvalue::OK, returnvalue::OK, diff --git a/mission/controller/acs/config/classIds.h b/mission/controller/acs/config/classIds.h index e714ff33..ccf6b616 100644 --- a/mission/controller/acs/config/classIds.h +++ b/mission/controller/acs/config/classIds.h @@ -5,15 +5,14 @@ #include namespace CLASS_ID { -enum eiveclassIds: uint8_t { - EIVE_CLASS_ID_START = COMMON_CLASS_ID_END, - KALMAN, - SAFE, - PTG, - DETUMBLE, - EIVE_CLASS_ID_END // [EXPORT] : [END] +enum eiveclassIds : uint8_t { + EIVE_CLASS_ID_START = COMMON_CLASS_ID_END, + KALMAN, + SAFE, + PTG, + DETUMBLE, + EIVE_CLASS_ID_END // [EXPORT] : [END] }; } - #endif /* ACS_CONFIG_CLASSIDS_H_ */ diff --git a/mission/controller/acs/control/CMakeLists.txt b/mission/controller/acs/control/CMakeLists.txt index dc540435..2d40ecc5 100644 --- a/mission/controller/acs/control/CMakeLists.txt +++ b/mission/controller/acs/control/CMakeLists.txt @@ -1,5 +1,2 @@ -target_sources( - ${LIB_EIVE_MISSION} - PRIVATE Detumble.cpp - PtgCtrl.cpp - SafeCtrl.cpp) \ No newline at end of file +target_sources(${LIB_EIVE_MISSION} PRIVATE Detumble.cpp PtgCtrl.cpp + SafeCtrl.cpp) diff --git a/mission/controller/acs/control/Detumble.cpp b/mission/controller/acs/control/Detumble.cpp index 7421226d..4c8217dc 100644 --- a/mission/controller/acs/control/Detumble.cpp +++ b/mission/controller/acs/control/Detumble.cpp @@ -6,30 +6,24 @@ * Author: Robin Marquardt */ - #include "Detumble.h" -#include "../util/MathOperations.h" -#include + #include #include #include #include #include +#include +#include "../util/MathOperations.h" -Detumble::Detumble(AcsParameters *acsParameters_){ - loadAcsParameters(acsParameters_); -} +Detumble::Detumble(AcsParameters *acsParameters_) { loadAcsParameters(acsParameters_); } -Detumble::~Detumble(){ - -} - -void Detumble::loadAcsParameters(AcsParameters *acsParameters_){ - - detumbleCtrlParameters = &(acsParameters_->detumbleCtrlParameters); - magnetorquesParameter = &(acsParameters_->magnetorquesParameter); +Detumble::~Detumble() {} +void Detumble::loadAcsParameters(AcsParameters *acsParameters_) { + detumbleCtrlParameters = &(acsParameters_->detumbleCtrlParameters); + magnetorquesParameter = &(acsParameters_->magnetorquesParameter); } ReturnValue_t Detumble::bDotLaw(const double *magRate, const bool magRateValid, diff --git a/mission/controller/acs/control/Detumble.h b/mission/controller/acs/control/Detumble.h index 375f67aa..bea9b1bf 100644 --- a/mission/controller/acs/control/Detumble.h +++ b/mission/controller/acs/control/Detumble.h @@ -8,38 +8,36 @@ #ifndef ACS_CONTROL_DETUMBLE_H_ #define ACS_CONTROL_DETUMBLE_H_ -#include "../SensorValues.h" -#include "../AcsParameters.h" -#include "../config/classIds.h" -#include -#include -#include #include +#include +#include +#include +#include "../AcsParameters.h" +#include "../SensorValues.h" +#include "../config/classIds.h" -class Detumble{ +class Detumble { + public: + Detumble(AcsParameters *acsParameters_); + virtual ~Detumble(); -public: - Detumble(AcsParameters *acsParameters_); - virtual ~Detumble(); + static const uint8_t INTERFACE_ID = CLASS_ID::DETUMBLE; + static const ReturnValue_t DETUMBLE_NO_SENSORDATA = MAKE_RETURN_CODE(0x01); - static const uint8_t INTERFACE_ID = CLASS_ID::DETUMBLE; - static const ReturnValue_t DETUMBLE_NO_SENSORDATA = MAKE_RETURN_CODE(0x01); + /* @brief: Load AcsParameters für this class + * @param: acsParameters_ Pointer to object which defines the ACS configuration parameters + */ + void loadAcsParameters(AcsParameters *acsParameters_); - /* @brief: Load AcsParameters für 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); - ReturnValue_t bDotLaw(const double *magRate, const bool magRateValid, - const double *magField, const bool magFieldValid, double *magMom); + ReturnValue_t bangbangLaw(const double *magRate, const bool magRateValid, double *magMom); - ReturnValue_t bangbangLaw(const double *magRate, const bool magRateValid, double *magMom); - - private: - AcsParameters::DetumbleCtrlParameters* detumbleCtrlParameters; - AcsParameters::MagnetorquesParameter* magnetorquesParameter; + private: + AcsParameters::DetumbleCtrlParameters *detumbleCtrlParameters; + AcsParameters::MagnetorquesParameter *magnetorquesParameter; }; #endif /*ACS_CONTROL_DETUMBLE_H_*/ - diff --git a/mission/controller/acs/control/PtgCtrl.cpp b/mission/controller/acs/control/PtgCtrl.cpp index e06b576f..07b595ec 100644 --- a/mission/controller/acs/control/PtgCtrl.cpp +++ b/mission/controller/acs/control/PtgCtrl.cpp @@ -5,10 +5,8 @@ * Author: Robin Marquardt */ - - #include "PtgCtrl.h" -#include "../util/MathOperations.h" + #include #include #include @@ -16,100 +14,96 @@ #include #include -PtgCtrl::PtgCtrl(AcsParameters *acsParameters_){ - loadAcsParameters(acsParameters_); +#include "../util/MathOperations.h" + +PtgCtrl::PtgCtrl(AcsParameters *acsParameters_) { loadAcsParameters(acsParameters_); } + +PtgCtrl::~PtgCtrl() {} + +void PtgCtrl::loadAcsParameters(AcsParameters *acsParameters_) { + pointingModeControllerParameters = &(acsParameters_->targetModeControllerParameters); + inertiaEIVE = &(acsParameters_->inertiaEIVE); + rwHandlingParameters = &(acsParameters_->rwHandlingParameters); + rwMatrices = &(acsParameters_->rwMatrices); } -PtgCtrl::~PtgCtrl(){ +void PtgCtrl::ptgGroundstation(const double mode, const double *qError, const double *deltaRate, + const double *rwPseudoInv, double *torqueRws) { + //------------------------------------------------------------------------------------------------ + // Compute gain matrix K and P matrix + //------------------------------------------------------------------------------------------------ + double om = pointingModeControllerParameters->om; + double zeta = pointingModeControllerParameters->zeta; + double qErrorMin = pointingModeControllerParameters->qiMin; + double omMax = pointingModeControllerParameters->omMax; -} + double cInt = 2 * om * zeta; + double kInt = 2 * pow(om, 2); -void PtgCtrl::loadAcsParameters(AcsParameters *acsParameters_){ - pointingModeControllerParameters = &(acsParameters_->targetModeControllerParameters); - inertiaEIVE = &(acsParameters_->inertiaEIVE); - rwHandlingParameters = &(acsParameters_->rwHandlingParameters); - rwMatrices =&(acsParameters_->rwMatrices); -} + double qErrorLaw[3] = {0, 0, 0}; -void PtgCtrl::ptgGroundstation(const double mode, const double *qError, const double *deltaRate,const double *rwPseudoInv, double *torqueRws){ + for (int i = 0; i < 3; i++) { + if (abs(qError[i]) < qErrorMin) { + qErrorLaw[i] = qErrorMin; + } else { + qErrorLaw[i] = abs(qError[i]); + } + } + double qErrorLawNorm = VectorOperations::norm(qErrorLaw, 3); - //------------------------------------------------------------------------------------------------ - // Compute gain matrix K and P matrix - //------------------------------------------------------------------------------------------------ - double om = pointingModeControllerParameters->om; - double zeta = pointingModeControllerParameters->zeta; - double qErrorMin = pointingModeControllerParameters->qiMin; - double omMax = pointingModeControllerParameters->omMax; + double gain1 = cInt * omMax / qErrorLawNorm; + double gainVector[3] = {0, 0, 0}; + VectorOperations::mulScalar(qErrorLaw, gain1, gainVector, 3); - double cInt = 2 * om * zeta; - double kInt = 2 * pow(om,2); + double gainMatrixDiagonal[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + double gainMatrix[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + gainMatrixDiagonal[0][0] = gainVector[0]; + gainMatrixDiagonal[1][1] = gainVector[1]; + gainMatrixDiagonal[2][2] = gainVector[2]; + MatrixOperations::multiply(*gainMatrixDiagonal, *(inertiaEIVE->inertiaMatrix), + *gainMatrix, 3, 3, 3); - double qErrorLaw[3] = {0, 0, 0}; + // Inverse of gainMatrix + double gainMatrixInverse[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + gainMatrixInverse[0][0] = 1 / gainMatrix[0][0]; + gainMatrixInverse[1][1] = 1 / gainMatrix[1][1]; + gainMatrixInverse[2][2] = 1 / gainMatrix[2][2]; - for (int i = 0; i < 3; i++) { - if (abs(qError[i]) < qErrorMin) { - qErrorLaw[i] = qErrorMin; - } - else { - qErrorLaw[i] = abs(qError[i]); - } - } - double qErrorLawNorm = VectorOperations::norm(qErrorLaw, 3); + double pMatrix[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; + MatrixOperations::multiply(*gainMatrixInverse, *(inertiaEIVE->inertiaMatrix), *pMatrix, 3, + 3, 3); + MatrixOperations::multiplyScalar(*pMatrix, kInt, *pMatrix, 3, 3); - double gain1 = cInt * omMax / qErrorLawNorm; - double gainVector[3] = {0, 0, 0}; - VectorOperations::mulScalar(qErrorLaw, gain1, gainVector, 3); + //------------------------------------------------------------------------------------------------ + // Torque Calculations for the reaction wheels + //------------------------------------------------------------------------------------------------ - double gainMatrixDiagonal[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - double gainMatrix[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - gainMatrixDiagonal[0][0] = gainVector[0]; - gainMatrixDiagonal[1][1] = gainVector[1]; - gainMatrixDiagonal[2][2] = gainVector[2]; - MatrixOperations::multiply( *gainMatrixDiagonal, *(inertiaEIVE->inertiaMatrix), *gainMatrix, 3, 3, 3); + double pError[3] = {0, 0, 0}; + MatrixOperations::multiply(*pMatrix, qError, pError, 3, 3, 1); + double pErrorSign[3] = {0, 0, 0}; - // Inverse of gainMatrix - double gainMatrixInverse[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - gainMatrixInverse[0][0] = 1 / gainMatrix[0][0]; - gainMatrixInverse[1][1] = 1 / gainMatrix[1][1]; - gainMatrixInverse[2][2] = 1 / gainMatrix[2][2]; + for (int i = 0; i < 3; i++) { + if (abs(pError[i]) > 1) { + pErrorSign[i] = sign(pError[i]); + } else { + pErrorSign[i] = pError[i]; + } + } + // Torque for quaternion error + double torqueQuat[3] = {0, 0, 0}; + MatrixOperations::multiply(*gainMatrix, pErrorSign, torqueQuat, 3, 3, 1); + VectorOperations::mulScalar(torqueQuat, -1, torqueQuat, 3); - double pMatrix[3][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; - MatrixOperations::multiply(*gainMatrixInverse, *(inertiaEIVE->inertiaMatrix), *pMatrix, 3, 3, 3); - MatrixOperations::multiplyScalar(*pMatrix, kInt, *pMatrix, 3, 3); - - //------------------------------------------------------------------------------------------------ - // Torque Calculations for the reaction wheels - //------------------------------------------------------------------------------------------------ - - double pError[3] = {0, 0, 0}; - MatrixOperations::multiply(*pMatrix, qError, pError, 3, 3, 1); - double pErrorSign[3] = {0, 0, 0}; - - for (int i = 0; i < 3; i++) { - - if (abs(pError[i]) > 1) { - pErrorSign[i] = sign(pError[i]); - } - else { - pErrorSign[i] = pError[i]; - } - } -// 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 - double torqueRate[3] = {0, 0, 0}; - MatrixOperations::multiply(*(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 - double torque[3] = {0, 0, 0}; - VectorOperations::add(torqueRate, torqueQuat, torque, 3); - MatrixOperations::multiply(rwPseudoInv, torque, torqueRws, 4, 3, 1); + // Torque for rate error + double torqueRate[3] = {0, 0, 0}; + MatrixOperations::multiply(*(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 + double torque[3] = {0, 0, 0}; + VectorOperations::add(torqueRate, torqueQuat, torque, 3); + MatrixOperations::multiply(rwPseudoInv, torque, torqueRws, 4, 3, 1); } void PtgCtrl::ptgDesaturation(double *magFieldEst, bool magFieldEstValid, double *satRate, diff --git a/mission/controller/acs/util/CholeskyDecomposition.h b/mission/controller/acs/util/CholeskyDecomposition.h index 38ce0bcc..667f9f63 100644 --- a/mission/controller/acs/util/CholeskyDecomposition.h +++ b/mission/controller/acs/util/CholeskyDecomposition.h @@ -8,95 +8,91 @@ #ifndef CHOLESKYDECOMPOSITION_H_ #define CHOLESKYDECOMPOSITION_H_ #include -//typedef unsigned int uint8_t; +// typedef unsigned int uint8_t; -template +template class CholeskyDecomposition { -public: - static int invertCholesky(T1 *matrix, T2 *result, T3 *tempMatrix, const uint8_t dimension) - { - // https://github.com/simondlevy/TinyEKF/blob/master/tiny_ekf.c - return cholsl(matrix, result, tempMatrix, dimension); - } -private: - // https://github.com/simondlevy/TinyEKF/blob/master/tiny_ekf.c - static uint8_t choldc1(double * a, double * p, uint8_t n) { - int8_t i,j,k; - double sum; + public: + static int invertCholesky(T1 *matrix, T2 *result, T3 *tempMatrix, const uint8_t dimension) { + // https://github.com/simondlevy/TinyEKF/blob/master/tiny_ekf.c + return cholsl(matrix, result, tempMatrix, dimension); + } - for (i = 0; i < n; i++) { - for (j = i; j < n; j++) { - sum = a[i*n+j]; - for (k = i - 1; k >= 0; k--) { - sum -= a[i*n+k] * a[j*n+k]; - } - if (i == j) { - if (sum <= 0) { - return 1; /* error */ - } - p[i] = sqrt(sum); - } - else { - a[j*n+i] = sum / p[i]; - } - } - } + private: + // https://github.com/simondlevy/TinyEKF/blob/master/tiny_ekf.c + static uint8_t choldc1(double *a, double *p, uint8_t n) { + int8_t i, j, k; + double sum; - return 0; /* success */ - } + for (i = 0; i < n; i++) { + for (j = i; j < n; j++) { + sum = a[i * n + j]; + for (k = i - 1; k >= 0; k--) { + sum -= a[i * n + k] * a[j * n + k]; + } + if (i == j) { + if (sum <= 0) { + return 1; /* error */ + } + p[i] = sqrt(sum); + } else { + a[j * n + i] = sum / p[i]; + } + } + } - // https://github.com/simondlevy/TinyEKF/blob/master/tiny_ekf.c - static uint8_t choldcsl(double * A, double * a, double * p, uint8_t n) - { - uint8_t i,j,k; double sum; - for (i = 0; i < n; i++) - for (j = 0; j < n; j++) - a[i*n+j] = A[i*n+j]; - if (choldc1(a, p, n)) return 1; - for (i = 0; i < n; i++) { - a[i*n+i] = 1 / p[i]; - for (j = i + 1; j < n; j++) { - sum = 0; - for (k = i; k < j; k++) { - sum -= a[j*n+k] * a[k*n+i]; - } - a[j*n+i] = sum / p[j]; - } - } + return 0; /* success */ + } - return 0; /* success */ - } + // https://github.com/simondlevy/TinyEKF/blob/master/tiny_ekf.c + static uint8_t choldcsl(double *A, double *a, double *p, uint8_t n) { + uint8_t i, j, k; + double sum; + for (i = 0; i < n; i++) + for (j = 0; j < n; j++) a[i * n + j] = A[i * n + j]; + if (choldc1(a, p, n)) return 1; + for (i = 0; i < n; i++) { + a[i * n + i] = 1 / p[i]; + for (j = i + 1; j < n; j++) { + sum = 0; + for (k = i; k < j; k++) { + sum -= a[j * n + k] * a[k * n + i]; + } + a[j * n + i] = sum / p[j]; + } + } + return 0; /* success */ + } - // https://github.com/simondlevy/TinyEKF/blob/master/tiny_ekf.c - static uint8_t cholsl(double * A,double * a,double * p, uint8_t n) - { - uint8_t i,j,k; - if (choldcsl(A,a,p,n)) return 1; - for (i = 0; i < n; i++) { - for (j = i + 1; j < n; j++) { - a[i*n+j] = 0.0; - } - } - for (i = 0; i < n; i++) { - a[i*n+i] *= a[i*n+i]; - for (k = i + 1; k < n; k++) { - a[i*n+i] += a[k*n+i] * a[k*n+i]; - } - for (j = i + 1; j < n; j++) { - for (k = j; k < n; k++) { - a[i*n+j] += a[k*n+i] * a[k*n+j]; - } - } - } - for (i = 0; i < n; i++) { - for (j = 0; j < i; j++) { - a[i*n+j] = a[j*n+i]; - } - } + // https://github.com/simondlevy/TinyEKF/blob/master/tiny_ekf.c + static uint8_t cholsl(double *A, double *a, double *p, uint8_t n) { + uint8_t i, j, k; + if (choldcsl(A, a, p, n)) return 1; + for (i = 0; i < n; i++) { + for (j = i + 1; j < n; j++) { + a[i * n + j] = 0.0; + } + } + for (i = 0; i < n; i++) { + a[i * n + i] *= a[i * n + i]; + for (k = i + 1; k < n; k++) { + a[i * n + i] += a[k * n + i] * a[k * n + i]; + } + for (j = i + 1; j < n; j++) { + for (k = j; k < n; k++) { + a[i * n + j] += a[k * n + i] * a[k * n + j]; + } + } + } + for (i = 0; i < n; i++) { + for (j = 0; j < i; j++) { + a[i * n + j] = a[j * n + i]; + } + } - return 0; /* success */ - } + return 0; /* success */ + } }; #endif /* CONTRIB_MATH_CHOLESKYDECOMPOSITION_H_ */ -- 2.34.1 From 0bbdd21d8176a2bb2c37c7aed6bf10fad5e45bc6 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Dec 2022 15:58:39 +0100 Subject: [PATCH 098/101] bump changelog --- CHANGELOG.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index a4df75d5..7a0258d1 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -16,6 +16,12 @@ list yields a list of all related PRs for each release. - Renamed `/dev/ul-plsv` to `/dev/ploc_supv`, is not a UART lite anymore - Renamed `/dev/i2c_eive` to `/dev/i2c_pl` and `/dev/i2c-2` to `/dev/i2c_ps`. PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/328 + +## Added + +- First version of ACS controller + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/329 + # [v1.17.0] 28.11.2022 ## Added -- 2.34.1 From b38afa5df3ce79833c0cc91c02b6dc6096c4becf Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Dec 2022 16:01:50 +0100 Subject: [PATCH 099/101] repoint json dependency --- thirdparty/json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/thirdparty/json b/thirdparty/json index fb1ee4f9..bc889afb 160000 --- a/thirdparty/json +++ b/thirdparty/json @@ -1 +1 @@ -Subproject commit fb1ee4f94b426a398969b2c96df9784be8e007e6 +Subproject commit bc889afb4c5bf1c0d8ee29ef35eaaf4c8bef8a5d -- 2.34.1 From 60418f6fdc25b5e81faf1de54ad0fa2c682e86a6 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 2 Dec 2022 11:38:51 +0100 Subject: [PATCH 100/101] small compile fixes --- mission/devices/devicedefinitions/GPSDefinitions.h | 1 + unittest/controller/testThermalController.cpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/mission/devices/devicedefinitions/GPSDefinitions.h b/mission/devices/devicedefinitions/GPSDefinitions.h index e842f54b..7653745f 100644 --- a/mission/devices/devicedefinitions/GPSDefinitions.h +++ b/mission/devices/devicedefinitions/GPSDefinitions.h @@ -3,6 +3,7 @@ #include "fsfw/datapoollocal/StaticLocalDataSet.h" #include "fsfw/devicehandlers/DeviceHandlerIF.h" +#include "eive/eventSubsystemIds.h" namespace GpsHyperion { diff --git a/unittest/controller/testThermalController.cpp b/unittest/controller/testThermalController.cpp index 3fac0f4e..1c5f63fe 100644 --- a/unittest/controller/testThermalController.cpp +++ b/unittest/controller/testThermalController.cpp @@ -13,7 +13,7 @@ TEST_CASE("Thermal Controller", "[ThermalController]") { const object_id_t THERMAL_CONTROLLER_ID = 0x123; new TemperatureSensorsDummy(); - new SusDummy(); + //new SusDummy(); // testEnvironment::initialize(); -- 2.34.1 From d72052fe2a64aa5efd45185c47252b4e0e33b59b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 2 Dec 2022 11:39:30 +0100 Subject: [PATCH 101/101] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 6e152818..d9fc58ab 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 6e152818707c7a12be8900bc239a0073053c0bec +Subproject commit d9fc58abed9df476a68d5dd4c798da6012fc597e -- 2.34.1