mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
AP_NavEKF: Fix bug preventing home position being set by copter
The interface definition has been modified so that it returns true for a position obtained usin geither the normal inertial navigation calculation, or a raw GPS measurement. This enables this function to be used to set a home position before flight.
This commit is contained in:
parent
0812e16008
commit
be04be9b43
@ -3755,7 +3755,9 @@ bool NavEKF::getMagOffsets(Vector3f &magOffsets) const
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Return the last calculated latitude, longitude and height in WGS-84
|
// Return the last calculated latitude, longitude and height in WGS-84
|
||||||
// If a calculated location isn't available, return false and the raw GPS measurement or last known position if available
|
// If a calculated location isn't available, return a raw GPS measurement
|
||||||
|
// The status will return true if a calculation or raw measurement is available
|
||||||
|
// The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control
|
||||||
bool NavEKF::getLLH(struct Location &loc) const
|
bool NavEKF::getLLH(struct Location &loc) const
|
||||||
{
|
{
|
||||||
if(validOrigin) {
|
if(validOrigin) {
|
||||||
@ -3778,11 +3780,12 @@ bool NavEKF::getLLH(struct Location &loc) const
|
|||||||
// we have a GPS position fix to return
|
// we have a GPS position fix to return
|
||||||
const struct Location &gpsloc = _ahrs->get_gps().location();
|
const struct Location &gpsloc = _ahrs->get_gps().location();
|
||||||
loc = gpsloc;
|
loc = gpsloc;
|
||||||
|
return true;
|
||||||
} else {
|
} else {
|
||||||
// if no GPS fix, provide last known position before entering the mode
|
// if no GPS fix, provide last known position before entering the mode
|
||||||
location_offset(loc, lastKnownPositionNE.x, lastKnownPositionNE.y);
|
location_offset(loc, lastKnownPositionNE.x, lastKnownPositionNE.y);
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// If no origin has been defined for the EKF, then we cannot use its position states so return a raw
|
// If no origin has been defined for the EKF, then we cannot use its position states so return a raw
|
||||||
|
@ -154,8 +154,9 @@ public:
|
|||||||
bool getMagOffsets(Vector3f &magOffsets) const;
|
bool getMagOffsets(Vector3f &magOffsets) const;
|
||||||
|
|
||||||
// Return the last calculated latitude, longitude and height in WGS-84
|
// Return the last calculated latitude, longitude and height in WGS-84
|
||||||
// If a calculated location isn't available, return false and the raw GPS measurement or last known position if available
|
// If a calculated location isn't available, return a raw GPS measurement
|
||||||
// If false returned, do not use for flight control
|
// The status will return true if a calculation or raw measurement is available
|
||||||
|
// The getFilterStatus() function provides a more detailed description of data health and must be checked if data is to be used for flight control
|
||||||
bool getLLH(struct Location &loc) const;
|
bool getLLH(struct Location &loc) const;
|
||||||
|
|
||||||
// return the latitude and longitude and height used to set the NED origin
|
// return the latitude and longitude and height used to set the NED origin
|
||||||
|
Loading…
Reference in New Issue
Block a user