Skip to content

Commit

Permalink
AP_NavEKF3: added timestamp for external position estimate
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed May 28, 2023
1 parent 29b21b0 commit 079b711
Show file tree
Hide file tree
Showing 4 changed files with 5 additions and 5 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_NavEKF3/AP_NavEKF3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1408,7 +1408,7 @@ bool NavEKF3::setOriginLLH(const Location &loc)
return ret;
}

bool NavEKF3::setLatLng(const Location &loc, float posAccuracy)
bool NavEKF3::setLatLng(const Location &loc, float posAccuracy, uint32_t timestamp_ms)
{
AP::dal().log_SetLatLng(loc, posAccuracy);

Expand All @@ -1417,7 +1417,7 @@ bool NavEKF3::setLatLng(const Location &loc, float posAccuracy)
}
bool ret = false;
for (uint8_t i=0; i<num_cores; i++) {
ret |= core[i].setLatLng(loc, posAccuracy);
ret |= core[i].setLatLng(loc, posAccuracy, timestamp_ms);
}
// return true if any core accepts the new origin
return ret;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3.h
Original file line number Diff line number Diff line change
Expand Up @@ -155,7 +155,7 @@ class NavEKF3 {
// Set the EKF's NE horizontal position states and their corresponding variances from a supplied WGS-84 location and uncertainty
// The altitude element of the location is not used.
// Returns true if the set was successful
bool setLatLng(const Location &loc, float posErr);
bool setLatLng(const Location &loc, float posErr, uint32_t timestamp_ms);

// return estimated height above ground level
// return false if ground height is not being estimated.
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ void NavEKF3_core::ResetPosition(resetDataSource posResetSource)
// Sets the EKF's NE horizontal position states and their corresponding variances from a supplied WGS-84 location and uncertainty
// The altitude element of the location is not used.
// Returns true if the set was successful
bool NavEKF3_core::setLatLng(const Location &loc, float posAccuracy)
bool NavEKF3_core::setLatLng(const Location &loc, float posAccuracy, uint32_t timestamp_ms)
{
if ((imuSampleTime_ms - lastPosPassTime_ms) < frontend->deadReckonDeclare_ms ||
(PV_AidingMode == AID_NONE)
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_NavEKF3/AP_NavEKF3_core.h
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,7 @@ class NavEKF3_core : public NavEKF_core_common
// Set the EKF's NE horizontal position states and their corresponding variances from a supplied WGS-84 location and uncertainty
// The altitude element of the location is not used.
// Returns true if the set was successful
bool setLatLng(const Location &loc, float posAccuracy);
bool setLatLng(const Location &loc, float posAccuracy, uint32_t timestamp_ms);

// return estimated height above ground level
// return false if ground height is not being estimated.
Expand Down

0 comments on commit 079b711

Please sign in to comment.