AP_DAL: fixed standalone linking

This commit is contained in:
Andrew Tridgell 2020-11-07 19:28:21 +11:00
parent 6fe05a9ab6
commit dd96d7c205
3 changed files with 8 additions and 4 deletions

View File

@ -247,7 +247,7 @@ bool AP_DAL::ekf_low_time_remaining(EKFType etype, uint8_t core)
{
static_assert(INS_MAX_INSTANCES <= 4, "max 4 IMUs");
const uint8_t mask = (1U<<(core+(uint8_t(etype)*4)));
#if !APM_BUILD_TYPE(APM_BUILD_Replay)
#if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay)
/*
if we have used more than 1/3 of the time for a loop then we
return true, indicating that we are low on CPU. This changes the

View File

@ -4,14 +4,12 @@
//
#include <AP_DAL/AP_DAL.h>
#include <AP_NavEKF3/AP_NavEKF3.h>
#include <AP_Logger/AP_Logger.h>
void AP_Param::setup_object_defaults(void const*, AP_Param::GroupInfo const*) {}
int AP_HAL::Util::vsnprintf(char*, unsigned long, char const*, va_list) { return -1; }
int AP_HAL::Util::vsnprintf(char*, size_t, char const*, va_list) { return -1; }
void *nologger = nullptr;
AP_Logger &AP::logger() {
@ -54,14 +52,20 @@ public:
AP_HAL_DAL_Standalone _hal;
const AP_HAL::HAL &hal = _hal;
#ifdef HAL_NO_GCS
NavEKF2 navekf2;
NavEKF3 navekf3;
#endif
int main(int argc, const char *argv[])
{
#ifdef HAL_NO_GCS
navekf2.InitialiseFilter();
navekf3.InitialiseFilter();
navekf2.UpdateFilter();
navekf3.UpdateFilter();
return navekf2.healthy() && navekf3.healthy()?0:1;
#else
return 0;
#endif
}