AP_NavEKF: fix documentation errors

This commit is contained in:
priseborough 2016-07-12 09:54:12 +10:00 committed by Andrew Tridgell
parent 01ce3e7f1e
commit b3bfb71431
4 changed files with 10 additions and 10 deletions

View File

@ -470,7 +470,7 @@ bool NavEKF::healthy(void) const
return core->healthy();
}
// Return the last calculated North East position relative to the reference point (m).
// Write the last calculated North East position relative to the reference point (m).
// If a calculated solution is not available, use the best available data and return false
// If false returned, do not use for flight control
bool NavEKF::getPosNE(Vector2f &posNE) const
@ -481,7 +481,7 @@ bool NavEKF::getPosNE(Vector2f &posNE) const
return core->getPosNE(posNE);
}
// Return the last calculated Down position relative to the reference point (m).
// Write the last calculated Down position relative to the reference point (m).
// If a calculated solution is not available, use the best available data and return false
// If false returned, do not use for flight control
bool NavEKF::getPosD(float &posD) const

View File

@ -71,12 +71,12 @@ public:
// Check basic filter health metrics and return a consolidated health status
bool healthy(void) const;
// Return the last calculated North East position relative to the reference point (m).
// Write the last calculated North East position relative to the reference point (m).
// If a calculated solution is not available, use the best available data and return false
// If false returned, do not use for flight control
bool getPosNE(Vector2f &posNE) const;
// Return the last calculated Down position relative to the reference point (m).
// Write the last calculated Down position relative to the reference point (m).
// If a calculated solution is not available, use the best available data and return false
// If false returned, do not use for flight control
bool getPosD(float &posD) const;

View File

@ -3358,8 +3358,8 @@ float NavEKF_core::getPosDownDerivative(void) const
return posDownDerivative;
}
// Return the last calculated NE position relative to the reference point (m).
// if a calculated solution is not available, use the best available data and return false
// Write the last calculated NE position relative to the reference point (m).
// Return true if the estimate is valid
bool NavEKF_core::getPosNE(Vector2f &posNE) const
{
// There are three modes of operation, absolute position (GPS fusion), relative position (optical flow fusion) and constant position (no position estimate available)
@ -3394,8 +3394,8 @@ bool NavEKF_core::getPosNE(Vector2f &posNE) const
return false;
}
// Return the last calculated D position relative to the reference point (m).
// if a calculated solution is not available, use the best available data and return false
// Write the last calculated D position relative to the reference point (m).
// Return true if the estimate is valid
bool NavEKF_core::getPosD(float &posD) const
{
// The EKF always has a height estimate regardless of mode of operation

View File

@ -114,12 +114,12 @@ public:
// Check basic filter health metrics and return a consolidated health status
bool healthy(void) const;
// Return the last calculated NE position relative to the reference point (m).
// Write the last calculated NE position relative to the reference point (m).
// If a calculated solution is not available, use the best available data and return false
// If false returned, do not use for flight control
bool getPosNE(Vector2f &posNE) const;
// Return the last calculated D position relative to the reference point (m).
// Write the last calculated D position relative to the reference point (m).
// If a calculated solution is not available, use the best available data and return false
// If false returned, do not use for flight control
bool getPosD(float &posD) const;