aboutsummaryrefslogtreecommitdiff
path: root/src/modules/fw_att_pos_estimator/estimator.h
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-02-05 13:22:58 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-02-05 13:22:58 +0100
commit30882e103b8551cbdd40db7c4bc4a8a809893d6a (patch)
treef0dffe043f8d3de94780ec92d4a1bfd0ec05c334 /src/modules/fw_att_pos_estimator/estimator.h
parent543fbf235dd26720b8880ff0b8553e292ac10f09 (diff)
downloadpx4-firmware-30882e103b8551cbdd40db7c4bc4a8a809893d6a.tar.gz
px4-firmware-30882e103b8551cbdd40db7c4bc4a8a809893d6a.tar.bz2
px4-firmware-30882e103b8551cbdd40db7c4bc4a8a809893d6a.zip
Moved to using references for arrays
Diffstat (limited to 'src/modules/fw_att_pos_estimator/estimator.h')
-rw-r--r--src/modules/fw_att_pos_estimator/estimator.h24
1 files changed, 11 insertions, 13 deletions
diff --git a/src/modules/fw_att_pos_estimator/estimator.h b/src/modules/fw_att_pos_estimator/estimator.h
index 2a0e43bb5..01a1ace99 100644
--- a/src/modules/fw_att_pos_estimator/estimator.h
+++ b/src/modules/fw_att_pos_estimator/estimator.h
@@ -134,41 +134,39 @@ void FuseMagnetometer();
void FuseAirspeed();
-void zeroRows(float covMat[n_states][n_states], uint8_t first, uint8_t last);
+void zeroRows(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last);
-void zeroCols(float covMat[n_states][n_states], uint8_t first, uint8_t last);
+void zeroCols(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last);
float sq(float valIn);
-void quatNorm(float quatOut[4], float quatIn[4]);
+void quatNorm(float (&quatOut)[4], const float quatIn[4]);
// store staes along with system time stamp in msces
void StoreStates(uint64_t timestamp_ms);
// recall stste vector stored at closest time to the one specified by msec
-void RecallStates(float statesForFusion[n_states], uint32_t msec);
+void RecallStates(float (&statesForFusion)[n_states], uint32_t msec);
-void quat2Tnb(Mat3f &Tnb, float quat[4]);
-
-void quat2Tbn(Mat3f &Tbn, float quat[4]);
+void quat2Tbn(Mat3f &Tbn, const float (&quat)[4]);
void calcEarthRateNED(Vector3f &omega, float latitude);
-void eul2quat(float quat[4], float eul[3]);
+void eul2quat(float (&quat)[4], const float (&eul)[3]);
-void quat2eul(float eul[3],float quat[4]);
+void quat2eul(float (&eul)[3], const float (&quat)[4]);
-void calcvelNED(float velNED[3], float gpsCourse, float gpsGndSpd, float gpsVelD);
+void calcvelNED(float (&velNED)[3], float gpsCourse, float gpsGndSpd, float gpsVelD);
-void calcposNED(float posNED[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
+void calcposNED(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
-void calcLLH(float posNED[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
+void calcLLH(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
void OnGroundCheck();
void CovarianceInit();
-void InitialiseFilter(float initvelNED[3]);
+void InitialiseFilter(float (&initvelNED)[3]);
uint32_t millis();