mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: fix documentation errors
This commit is contained in:
parent
b3bfb71431
commit
230ba2700f
|
@ -673,7 +673,7 @@ int8_t NavEKF2::getPrimaryCoreIndex(void) const
|
|||
return primary;
|
||||
}
|
||||
|
||||
// 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 NavEKF2::getPosNE(int8_t instance, Vector2f &posNE)
|
||||
|
@ -685,7 +685,7 @@ bool NavEKF2::getPosNE(int8_t instance, Vector2f &posNE)
|
|||
return core[instance].getPosNE(posNE);
|
||||
}
|
||||
|
||||
// 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 NavEKF2::getPosD(int8_t instance, float &posD)
|
||||
|
|
|
@ -62,13 +62,13 @@ public:
|
|||
// return -1 if no primary core selected
|
||||
int8_t getPrimaryCoreIndex(void) const;
|
||||
|
||||
// Return the last calculated NE position relative to the reference point (m) for the specified instance.
|
||||
// Write the last calculated NE position relative to the reference point (m) for the specified instance.
|
||||
// An out of range instance (eg -1) returns data for the the primary instance
|
||||
// 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(int8_t instance, Vector2f &posNE);
|
||||
|
||||
// Return the last calculated D position relative to the reference point (m) for the specified instance.
|
||||
// Write the last calculated D position relative to the reference point (m) for the specified instance.
|
||||
// An out of range instance (eg -1) returns data for the the primary instance
|
||||
// If a calculated solution is not available, use the best available data and return false
|
||||
// If false returned, do not use for flight control
|
||||
|
|
|
@ -209,7 +209,7 @@ void NavEKF2_core::getAccelZBias(float &zbias) const {
|
|||
}
|
||||
}
|
||||
|
||||
// Return the last estimated NE position relative to the reference point (m).
|
||||
// Write the last estimated NE position relative to the reference point (m).
|
||||
// Return true if the estimate is valid
|
||||
bool NavEKF2_core::getPosNE(Vector2f &posNE) const
|
||||
{
|
||||
|
@ -245,7 +245,7 @@ bool NavEKF2_core::getPosNE(Vector2f &posNE) const
|
|||
return false;
|
||||
}
|
||||
|
||||
// Return the last calculated D position relative to the reference point (m).
|
||||
// Write the last calculated D position relative to the reference point (m).
|
||||
// Return true if the estimte is valid
|
||||
bool NavEKF2_core::getPosD(float &posD) const
|
||||
{
|
||||
|
|
|
@ -66,12 +66,12 @@ public:
|
|||
// Intended to be used by the front-end to determine which is the primary EKF
|
||||
float faultScore(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;
|
||||
|
|
Loading…
Reference in New Issue