2021-01-18 21:53:20 -04:00
|
|
|
/*
|
|
|
|
feature selection for EKF3
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
2021-12-06 00:11:22 -04:00
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
2022-01-27 20:09:44 -04:00
|
|
|
#include <AP_Beacon/AP_Beacon_config.h>
|
2023-05-13 20:55:30 -03:00
|
|
|
#include <AP_AHRS/AP_AHRS_config.h>
|
2023-02-10 03:46:40 -04:00
|
|
|
#include <AP_OpticalFlow/AP_OpticalFlow_config.h>
|
2021-01-18 21:53:20 -04:00
|
|
|
|
|
|
|
// define for when to include all features
|
|
|
|
#define EK3_FEATURE_ALL APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) || APM_BUILD_TYPE(APM_BUILD_Replay)
|
|
|
|
|
|
|
|
// body odomotry (which includes wheel encoding) on rover or 2M boards
|
2021-01-19 00:27:03 -04:00
|
|
|
#ifndef EK3_FEATURE_BODY_ODOM
|
2021-01-18 21:53:20 -04:00
|
|
|
#define EK3_FEATURE_BODY_ODOM EK3_FEATURE_ALL || APM_BUILD_TYPE(APM_BUILD_Rover) || BOARD_FLASH_SIZE > 1024
|
2021-01-19 00:27:03 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
// external navigation on 2M boards
|
|
|
|
#ifndef EK3_FEATURE_EXTERNAL_NAV
|
|
|
|
#define EK3_FEATURE_EXTERNAL_NAV EK3_FEATURE_ALL || BOARD_FLASH_SIZE > 1024
|
|
|
|
#endif
|
|
|
|
|
2021-01-19 00:36:39 -04:00
|
|
|
// drag fusion on 2M boards
|
|
|
|
#ifndef EK3_FEATURE_DRAG_FUSION
|
|
|
|
#define EK3_FEATURE_DRAG_FUSION EK3_FEATURE_ALL || BOARD_FLASH_SIZE > 1024
|
|
|
|
#endif
|
|
|
|
|
2022-01-27 20:09:44 -04:00
|
|
|
// Beacon Fusion if beacon data available
|
|
|
|
#ifndef EK3_FEATURE_BEACON_FUSION
|
|
|
|
#define EK3_FEATURE_BEACON_FUSION AP_BEACON_ENABLED
|
|
|
|
#endif
|
2023-05-13 20:55:30 -03:00
|
|
|
|
|
|
|
#ifndef EK3_FEATURE_POSITION_RESET
|
|
|
|
#define EK3_FEATURE_POSITION_RESET EK3_FEATURE_ALL || AP_AHRS_POSITION_RESET_ENABLED
|
|
|
|
#endif
|
2023-11-07 18:23:40 -04:00
|
|
|
|
|
|
|
// rangefinder measurements if available
|
|
|
|
#ifndef EK3_FEATURE_RANGEFINDER_MEASUREMENTS
|
|
|
|
#define EK3_FEATURE_RANGEFINDER_MEASUREMENTS AP_RANGEFINDER_ENABLED
|
|
|
|
#endif
|
2023-02-10 03:46:40 -04:00
|
|
|
|
|
|
|
// Flow Fusion if Flow data available
|
|
|
|
#ifndef EK3_FEATURE_OPTFLOW_FUSION
|
|
|
|
#define EK3_FEATURE_OPTFLOW_FUSION HAL_NAVEKF3_AVAILABLE && AP_OPTICALFLOW_ENABLED
|
|
|
|
#endif
|