mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 18:53:57 -04:00
We will reserve BOARD_FLASH_SIZE for the internal flash on stm32 flash processors, use HAL_PROGRAM_SIZE_LIMIT_KB in the general code base. Notable change here is that boards with external flash will start to get features only available with more than 2MB of program storage
52 lines
1.7 KiB
C
52 lines
1.7 KiB
C
#pragma once
|
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
|
|
|
// Enabled 0 is compiled out (disabled)
|
|
// Enabled 1 is always enabled on all vehicles
|
|
// Enabled 2 is enabled with dummy methods for all vehicles except Sub and SITL
|
|
|
|
#ifndef AP_TEMPERATURE_SENSOR_ENABLED
|
|
#if HAL_PROGRAM_SIZE_LIMIT_KB <= 1024
|
|
#define AP_TEMPERATURE_SENSOR_ENABLED 0
|
|
#elif HAL_PROGRAM_SIZE_LIMIT_KB > 2048
|
|
#define AP_TEMPERATURE_SENSOR_ENABLED 1
|
|
#else
|
|
#define AP_TEMPERATURE_SENSOR_ENABLED 2
|
|
#endif
|
|
#endif
|
|
|
|
#ifndef AP_TEMPERATURE_SENSOR_BACKEND_DEFAULT_ENABLED
|
|
#define AP_TEMPERATURE_SENSOR_BACKEND_DEFAULT_ENABLED AP_TEMPERATURE_SENSOR_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_TEMPERATURE_SENSOR_MAX31865_ENABLED
|
|
#define AP_TEMPERATURE_SENSOR_MAX31865_ENABLED AP_TEMPERATURE_SENSOR_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_TEMPERATURE_SENSOR_ANALOG_ENABLED
|
|
#define AP_TEMPERATURE_SENSOR_ANALOG_ENABLED AP_TEMPERATURE_SENSOR_BACKEND_DEFAULT_ENABLED
|
|
#endif
|
|
|
|
#ifndef AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED
|
|
#define AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED AP_TEMPERATURE_SENSOR_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS
|
|
#endif
|
|
#if AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED && !HAL_ENABLE_DRONECAN_DRIVERS
|
|
#error AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED requires HAL_ENABLE_DRONECAN_DRIVERS
|
|
#endif
|
|
|
|
#ifndef AP_TEMPERATURE_SENSOR_MLX90614_ENABLED
|
|
#define AP_TEMPERATURE_SENSOR_MLX90614_ENABLED AP_TEMPERATURE_SENSOR_ENABLED
|
|
#endif
|
|
|
|
// maximum number of Temperature Sensors
|
|
#ifndef AP_TEMPERATURE_SENSOR_MAX_INSTANCES
|
|
#define AP_TEMPERATURE_SENSOR_MAX_INSTANCES 3
|
|
#endif
|
|
|
|
// first sensor is always the primary sensor
|
|
#ifndef AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE
|
|
#define AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE 0
|
|
#endif
|
|
|