aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorJohan Jansen <jnsn.johan@gmail.com>2015-02-05 13:25:05 +0100
committerJohan Jansen <jnsn.johan@gmail.com>2015-02-11 13:38:59 +0100
commit723c138b09663128fe2f5309bbe77b4ce22ef5fa (patch)
tree20f0623184ebcaf32bc07c83560a9f6de62cd090 /src
parent83298110c1dcb37a734d0140b7067ad7dd267e26 (diff)
downloadpx4-firmware-723c138b09663128fe2f5309bbe77b4ce22ef5fa.tar.gz
px4-firmware-723c138b09663128fe2f5309bbe77b4ce22ef5fa.tar.bz2
px4-firmware-723c138b09663128fe2f5309bbe77b4ce22ef5fa.zip
AttPosEKF: Move documentation to header file
Diffstat (limited to 'src')
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp36
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_22states.cpp28
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_22states.h38
3 files changed, 50 insertions, 52 deletions
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index eabef2798..fb88fa8e8 100644
--- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -332,13 +332,13 @@ private:
namespace estimator
{
-/* oddly, ERROR is not defined for c++ */
-#ifdef ERROR
-# undef ERROR
-#endif
-static const int ERROR = -1;
+ /* oddly, ERROR is not defined for c++ */
+ #ifdef ERROR
+ # undef ERROR
+ #endif
+ static const int ERROR = -1;
-AttitudePositionEstimatorEKF *g_estimator = nullptr;
+ AttitudePositionEstimatorEKF *g_estimator = nullptr;
}
AttitudePositionEstimatorEKF::AttitudePositionEstimatorEKF() :
@@ -525,16 +525,14 @@ AttitudePositionEstimatorEKF::~AttitudePositionEstimatorEKF()
estimator::g_estimator = nullptr;
}
-int
-AttitudePositionEstimatorEKF::enable_logging(bool logging)
+int AttitudePositionEstimatorEKF::enable_logging(bool logging)
{
_ekf_logging = logging;
return 0;
}
-int
-AttitudePositionEstimatorEKF::parameters_update()
+int AttitudePositionEstimatorEKF::parameters_update()
{
param_get(_parameter_handles.vel_delay_ms, &(_parameters.vel_delay_ms));
@@ -578,8 +576,7 @@ AttitudePositionEstimatorEKF::parameters_update()
return OK;
}
-void
-AttitudePositionEstimatorEKF::vehicle_status_poll()
+void AttitudePositionEstimatorEKF::vehicle_status_poll()
{
bool vstatus_updated;
@@ -592,8 +589,7 @@ AttitudePositionEstimatorEKF::vehicle_status_poll()
}
}
-int
-AttitudePositionEstimatorEKF::check_filter_state()
+int AttitudePositionEstimatorEKF::check_filter_state()
{
/*
* CHECK IF THE INPUT DATA IS SANE
@@ -709,14 +705,12 @@ AttitudePositionEstimatorEKF::check_filter_state()
return check;
}
-void
-AttitudePositionEstimatorEKF::task_main_trampoline(int argc, char *argv[])
+void AttitudePositionEstimatorEKF::task_main_trampoline(int argc, char *argv[])
{
estimator::g_estimator->task_main();
}
-void
-AttitudePositionEstimatorEKF::task_main()
+void AttitudePositionEstimatorEKF::task_main()
{
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
@@ -1637,8 +1631,7 @@ AttitudePositionEstimatorEKF::task_main()
_exit(0);
}
-int
-AttitudePositionEstimatorEKF::start()
+int AttitudePositionEstimatorEKF::start()
{
ASSERT(_estimator_task == -1);
@@ -1658,8 +1651,7 @@ AttitudePositionEstimatorEKF::start()
return OK;
}
-void
-AttitudePositionEstimatorEKF::print_status()
+void AttitudePositionEstimatorEKF::print_status()
{
math::Quaternion q(_ekf->states[0], _ekf->states[1], _ekf->states[2], _ekf->states[3]);
math::Matrix<3, 3> R = q.to_dcm();
diff --git a/src/modules/ekf_att_pos_estimator/estimator_22states.cpp b/src/modules/ekf_att_pos_estimator/estimator_22states.cpp
index 4e4ef3b92..28d0fde34 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_22states.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator_22states.cpp
@@ -2049,11 +2049,6 @@ void AttPosEKF::FuseOptFlow()
}
}
-/*
-Estimation of optical flow sensor focal length scale factor and terrain height using a two state EKF
-This fiter requires optical flow rates that are not motion compensated
-Range to ground measurement is assumed to be via a narrow beam type sensor - eg laser
-*/
void AttPosEKF::OpticalFlowEKF()
{
// propagate ground position state noise each time this is called using the difference in position since the last observations and an RMS gradient assumption
@@ -2806,12 +2801,6 @@ bool AttPosEKF::FilterHealthy()
return true;
}
-/**
- * Reset the filter position states
- *
- * This resets the position to the last GPS measurement
- * or to zero in case of static position.
- */
void AttPosEKF::ResetPosition(void)
{
if (staticMode) {
@@ -2825,20 +2814,12 @@ void AttPosEKF::ResetPosition(void)
}
}
-/**
- * Reset the height state.
- *
- * This resets the height state with the last altitude measurements
- */
void AttPosEKF::ResetHeight(void)
{
// write to the state vector
states[9] = -hgtMea;
}
-/**
- * Reset the velocity state.
- */
void AttPosEKF::ResetVelocity(void)
{
if (staticMode) {
@@ -2931,15 +2912,6 @@ out:
}
-/**
- * Check the filter inputs and bound its operational state
- *
- * This check will reset the filter states if required
- * due to a failure of consistency or timeout checks.
- * it should be run after the measurement data has been
- * updated, but before any of the fusion steps are
- * executed.
- */
int AttPosEKF::CheckAndBound(struct ekf_status_report *last_error)
{
diff --git a/src/modules/ekf_att_pos_estimator/estimator_22states.h b/src/modules/ekf_att_pos_estimator/estimator_22states.h
index 898105db4..be382127b 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_22states.h
+++ b/src/modules/ekf_att_pos_estimator/estimator_22states.h
@@ -230,6 +230,12 @@ public:
void FuseOptFlow();
+ /**
+ * @brief
+ * Estimation of optical flow sensor focal length scale factor and terrain height using a two state EKF
+ * This fiter requires optical flow rates that are not motion compensated
+ * Range to ground measurement is assumed to be via a narrow beam type sensor - eg laser
+ **/
void OpticalFlowEKF();
void zeroRows(float (&covMat)[EKF_STATE_ESTIMATES][EKF_STATE_ESTIMATES], uint8_t first, uint8_t last);
@@ -290,10 +296,31 @@ public:
void ForceSymmetry();
+ /**
+ * @brief
+ * Check the filter inputs and bound its operational state
+ *
+ * This check will reset the filter states if required
+ * due to a failure of consistency or timeout checks.
+ * it should be run after the measurement data has been
+ * updated, but before any of the fusion steps are
+ * executed.
+ */
int CheckAndBound(struct ekf_status_report *last_error);
+ /**
+ * @brief
+ * Reset the filter position states
+ *
+ * This resets the position to the last GPS measurement
+ * or to zero in case of static position.
+ */
void ResetPosition();
+ /**
+ * @brief
+ * Reset the velocity state.
+ */
void ResetVelocity();
void ZeroVariables();
@@ -309,7 +336,8 @@ public:
protected:
/**
- * @brief Initializes algorithm parameters to safe default values
+ * @brief
+ * Initializes algorithm parameters to safe default values
**/
void InitialiseParameters();
@@ -321,7 +349,13 @@ protected:
bool VelNEDDiverged();
- void ResetHeight(void);
+ /**
+ * @brief
+ * Reset the height state.
+ *
+ * This resets the height state with the last altitude measurements
+ */
+ void ResetHeight();
void AttitudeInit(float ax, float ay, float az, float mx, float my, float mz, float declination, float *initQuat);