6db09c9fdd
decimate the gyro window locally configure rate loop buffer based on AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED allow backends to be updated from rate thread output debug error if rate loop buffer overruns add support for updating filter parameters independently of propagating samples add rate loop config abstraction that allows code to be elided on non-copter builds must be using harmonic notch to use rate thread mediate fast rate loop buffer using mutex and binary semaphore ensure gyro samples are used when the rate loop buffer isn't Co-Authored-By: Andrew Tridgell <andrew@tridgell.net>
10 lines
390 B
C
10 lines
390 B
C
#pragma once
|
|
|
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
|
#include <AP_InertialSensor/AP_InertialSensor_config.h>
|
|
|
|
#ifndef AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
|
|
#define AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED (AP_INERTIALSENSOR_ENABLED && HAL_INS_RATE_LOOP && AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED && APM_BUILD_TYPE(APM_BUILD_ArduCopter))
|
|
#endif
|