ardupilot/libraries/AP_RPM/AP_RPM_config.h

49 lines
1.3 KiB
C

#pragma once
#include <AP_HAL/AP_HAL_Boards.h>
#include <AP_EFI/AP_EFI_config.h>
#include <AP_Generator/AP_Generator_config.h>
#include <AP_InertialSensor/AP_InertialSensor_config.h>
#include <AP_ESC_Telem/AP_ESC_Telem_config.h>
#ifndef AP_RPM_ENABLED
#define AP_RPM_ENABLED 1
#endif
#ifndef RPM_MAX_INSTANCES
#define RPM_MAX_INSTANCES 2
#endif
#ifndef AP_RPM_BACKEND_DEFAULT_ENABLED
#define AP_RPM_BACKEND_DEFAULT_ENABLED AP_RPM_ENABLED
#endif
#ifndef AP_RPM_EFI_ENABLED
#define AP_RPM_EFI_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && HAL_EFI_ENABLED
#endif
#ifndef AP_RPM_ESC_TELEM_ENABLED
#define AP_RPM_ESC_TELEM_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_RPM_HARMONICNOTCH_ENABLED
#define AP_RPM_HARMONICNOTCH_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && AP_INERTIALSENSOR_ENABLED
#endif
#ifndef AP_RPM_PIN_ENABLED
#define AP_RPM_PIN_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED
#endif
#ifndef AP_RPM_SIM_ENABLED
#define AP_RPM_SIM_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && AP_SIM_ENABLED
#endif
#ifndef AP_RPM_GENERATOR_ENABLED
#define AP_RPM_GENERATOR_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && HAL_GENERATOR_ENABLED
#endif
#ifndef AP_RPM_ESC_TELEM_OUTBOUND_ENABLED
#define AP_RPM_ESC_TELEM_OUTBOUND_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && HAL_WITH_ESC_TELEM
#endif