AP_NavEKF3: removed have_ekf_logging

This commit is contained in:
Andrew Tridgell 2020-11-07 16:59:41 +11:00
parent 21dfdc2192
commit 1bdf6173ec
3 changed files with 0 additions and 5 deletions

View File

@ -389,9 +389,6 @@ public:
// allow the enable flag to be set by Replay
void set_enable(bool enable) { _enable.set_enable(enable); }
// are we doing sensor logging inside the EKF?
bool have_ekf_logging(void) const { return false; }
// get timing statistics structure
void getTimingStatistics(int8_t instance, struct ekf_timing &timing) const;

View File

@ -4,7 +4,6 @@
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_DAL/AP_DAL.h>
#include <stdio.h>
/********************************************************
* OPT FLOW AND RANGE FINDER *

View File

@ -456,7 +456,6 @@ timee to reduce the resulting tilt error. Yaw alignment is not performed by this
function, but is perfomred later and initiated the SelectMagFusion() function
after the tilt has stabilised.
*/
#include <stdio.h>
bool NavEKF3_core::InitialiseFilterBootstrap(void)
{