mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_ChibiOS: add defines for all battery backends
This commit is contained in:
parent
85501f8219
commit
b52f54d480
@ -39,7 +39,7 @@ AP_BattMonitor_INA239::AP_BattMonitor_INA239(AP_BattMonitor &mon,
|
||||
|
||||
void AP_BattMonitor_INA239::init(void)
|
||||
{
|
||||
dev = hal.spi->get_device(HAL_BATTMON_INA239_SPI_DEVICE);
|
||||
dev = hal.spi->get_device(AP_BATTERY_INA239_SPI_DEVICE);
|
||||
if (!dev) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "device fail");
|
||||
return;
|
||||
|
@ -161,7 +161,7 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
||||
# save some flash
|
||||
include ../include/minimal_GPS.inc
|
||||
include ../include/save_some_flash.inc
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
define AP_BATTMON_SYNTHETIC_CURRENT_ENABLED 0
|
||||
define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 0
|
||||
|
@ -65,7 +65,7 @@ include ../include/save_some_flash.inc
|
||||
define AP_GRIPPER_ENABLED 0
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
|
||||
# only include ublox GPS driver
|
||||
include ../include/minimal_GPS.inc
|
||||
|
@ -16,7 +16,7 @@ define AP_NOTIFY_OREOLED_ENABLED 1
|
||||
undef HAL_SOLO_GIMBAL_ENABLED
|
||||
define HAL_SOLO_GIMBAL_ENABLED HAL_MOUNT_ENABLED
|
||||
|
||||
undef AP_BATTMON_SMBUS_SOLO_ENABLED
|
||||
define AP_BATTMON_SMBUS_SOLO_ENABLED AP_BATTMON_SMBUS_ENABLE
|
||||
undef AP_BATTERY_SMBUS_SOLO_ENABLED
|
||||
define AP_BATTERY_SMBUS_SOLO_ENABLED AP_BATTERY_SMBUS_ENABLED
|
||||
|
||||
AUTOBUILD_TARGETS Copter
|
||||
|
@ -328,8 +328,8 @@ DMA_NOSHARE SPI1* SPI4* USART6*
|
||||
define AP_NOTIFY_OREOLED_ENABLED 1
|
||||
define HAL_SOLO_GIMBAL_ENABLED HAL_MOUNT_ENABLED
|
||||
|
||||
undef AP_BATTMON_SMBUS_SOLO_ENABLED
|
||||
define AP_BATTMON_SMBUS_SOLO_ENABLED AP_BATTMON_SMBUS_ENABLE
|
||||
undef AP_BATTERY_SMBUS_SOLO_ENABLED
|
||||
define AP_BATTERY_SMBUS_SOLO_ENABLED AP_BATTERY_SMBUS_ENABLED
|
||||
|
||||
# Enable Sagetech MXS ADSB transponder
|
||||
define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_ENABLED
|
||||
|
@ -57,7 +57,7 @@ define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5
|
||||
undef HAL_SOLO_GIMBAL_ENABLED
|
||||
define HAL_SOLO_GIMBAL_ENABLED HAL_MOUNT_ENABLED
|
||||
|
||||
undef AP_BATTMON_SMBUS_SOLO_ENABLED
|
||||
define AP_BATTMON_SMBUS_SOLO_ENABLED AP_BATTMON_SMBUS_ENABLE
|
||||
undef AP_BATTERY_SMBUS_SOLO_ENABLED
|
||||
define AP_BATTERY_SMBUS_SOLO_ENABLED AP_BATTERY_SMBUS_ENABLED
|
||||
|
||||
AUTOBUILD_TARGETS Copter
|
||||
|
@ -163,7 +163,7 @@ define HAL_BATT_CURR_SCALE 25
|
||||
|
||||
# minimal drivers to reduce flash usage
|
||||
include ../include/minimal.inc
|
||||
define AP_BATTMON_SYNTHETIC_CURRENT_ENABLED 0
|
||||
define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 0
|
||||
|
||||
# enable IMU fast sampling
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 1
|
||||
|
@ -170,4 +170,4 @@ define HAL_PARACHUTE_ENABLED 0
|
||||
# minimal drivers to reduce flash usage
|
||||
include ../include/minimal.inc
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
|
@ -155,7 +155,7 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
||||
define HAL_GYROFFT_ENABLED 0
|
||||
|
||||
# --------------------- save flash ----------------------
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
define AP_BATT_MONITOR_MAX_INSTANCES 1
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
|
@ -41,7 +41,7 @@ define STM32_PWM_USE_ADVANCED TRUE
|
||||
|
||||
# save some flash
|
||||
include ../include/save_some_flash.inc
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
define HAL_MOUNT_ENABLED 0
|
||||
|
@ -150,7 +150,7 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
define STM32_PWM_USE_ADVANCED TRUE
|
||||
|
||||
# disable SMBUS battery monitors to save flash
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
|
||||
# disable parachute to save flash
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
|
@ -156,7 +156,7 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin
|
||||
define STM32_PWM_USE_ADVANCED TRUE
|
||||
|
||||
# disable SMBUS battery monitors to save flash
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
|
||||
# disable parachute and sprayer to save flash
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
|
@ -169,7 +169,7 @@ define HAL_BATT2_VOLT_SCALE 11.0
|
||||
include ../include/minimize_features.inc
|
||||
include ../include/minimal_GPS.inc
|
||||
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
|
||||
# reduce max size of embedded params for apj_tool.py
|
||||
|
@ -180,7 +180,7 @@ define HAL_GYROFFT_ENABLED 0
|
||||
# --------------------- save flash ----------------------
|
||||
# save some flash
|
||||
include ../include/save_some_flash.inc
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
define AP_GRIPPER_ENABLED 0
|
||||
@ -190,4 +190,4 @@ define HAL_NMEA_OUTPUT_ENABLED 0
|
||||
define HAL_BUTTON_ENABLED 0
|
||||
define AP_NOTIFY_OREOLED_ENABLED 0
|
||||
define HAL_PICCOLO_CAN_ENABLE 0
|
||||
define AP_BATTMON_SYNTHETIC_CURRENT_ENABLED 0
|
||||
define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 0
|
||||
|
@ -185,7 +185,7 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin
|
||||
define STM32_PWM_USE_ADVANCED TRUE
|
||||
|
||||
# disable SMBUS battery monitors to save flash
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
|
||||
# disable parachute and sprayer to save flash
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
@ -198,8 +198,8 @@ define HAL_GYROFFT_ENABLED 0
|
||||
# save some flash
|
||||
include ../include/save_some_flash.inc
|
||||
define AP_GRIPPER_ENABLED 0
|
||||
define AP_BATTMON_SYNTHETIC_CURRENT_ENABLED 0
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
define HAL_RUNCAM_ENABLED 0
|
||||
|
@ -160,7 +160,7 @@ define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin
|
||||
|
||||
# disable SMBUS battery monitors to save flash
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
|
||||
# disable parachute and sprayer to save flash
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
|
@ -4,8 +4,8 @@ define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-BattMon"
|
||||
|
||||
# enable battery monitor
|
||||
define HAL_PERIPH_ENABLE_BATTERY
|
||||
define HAL_BATTMON_INA239_ENABLED 1
|
||||
define HAL_BATTMON_INA239_SPI_DEVICE "INA23X"
|
||||
define AP_BATTERY_INA239_ENABLED 1
|
||||
define AP_BATTERY_INA239_SPI_DEVICE "INA23X"
|
||||
define HAL_BATT_MONITOR_DEFAULT 26
|
||||
define AP_PERIPH_BATTERY_MODEL_NAME "MatekL431-BattMon"
|
||||
|
||||
|
@ -126,7 +126,7 @@ define HAL_I2C_INTERNAL_MASK 0
|
||||
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||
|
||||
# disable SMBUS monitors to save flash
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
|
||||
# disable parachute and sprayer to save flash
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
|
@ -151,5 +151,6 @@ include ../include/minimal.inc
|
||||
define AP_GRIPPER_ENABLED 0
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
define HAL_SPRAYER_ENABLED 0
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTMON_FUEL_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
define AP_BATTERY_FUELFLOW_ENABLED 0
|
||||
define AP_BATTERY_FUELLEVEL_PWM_ENABLED 0
|
||||
|
@ -473,8 +473,8 @@ ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin
|
||||
define AP_NOTIFY_OREOLED_ENABLED (BOARD_FLASH_SIZE > 1024)
|
||||
define HAL_SOLO_GIMBAL_ENABLED (HAL_MOUNT_ENABLED && BOARD_FLASH_SIZE > 1024)
|
||||
|
||||
undef AP_BATTMON_SMBUS_SOLO_ENABLED
|
||||
define AP_BATTMON_SMBUS_SOLO_ENABLED (AP_BATTMON_SMBUS_ENABLE && BOARD_FLASH_SIZE > 1024)
|
||||
undef AP_BATTERY_SMBUS_SOLO_ENABLED
|
||||
define AP_BATTERY_SMBUS_SOLO_ENABLED (AP_BATTERY_SMBUS_ENABLED && BOARD_FLASH_SIZE > 1024)
|
||||
|
||||
# produce this error if we are on a 1M board
|
||||
define BOARD_CHECK_F427_USE_1M "ERROR: 1M flash use fmuv2"
|
||||
|
@ -153,7 +153,7 @@ define STM32_PWM_USE_ADVANCED TRUE
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin
|
||||
|
||||
# disable SMBUS monitors to save flash
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
|
||||
# disable parachute and sprayer to save flash
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
@ -164,7 +164,7 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
||||
|
||||
# save some flash
|
||||
include ../include/save_some_flash.inc
|
||||
define AP_BATTMON_SYNTHETIC_CURRENT_ENABLED 0
|
||||
define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 0
|
||||
|
||||
# only include ublox GPS driver
|
||||
include ../include/minimal_GPS.inc
|
||||
|
@ -20,7 +20,7 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
# disable SMBUS monitors to save flash
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_SMBUS_ENABLED 0
|
||||
|
||||
# disable parachute and sprayer to save flash
|
||||
define HAL_PARACHUTE_ENABLED 0
|
||||
|
@ -2992,8 +2992,8 @@ def add_apperiph_defaults(f):
|
||||
#endif
|
||||
|
||||
// disable various battery monitor backends:
|
||||
#ifndef AP_BATTMON_SYNTHETIC_CURRENT_ENABLED
|
||||
#define AP_BATTMON_SYNTHETIC_CURRENT_ENABLED 0
|
||||
#ifndef AP_BATTERY_SYNTHETIC_CURRENT_ENABLED
|
||||
#define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 0
|
||||
#endif
|
||||
|
||||
#ifndef AP_BATT_MONITOR_MAX_INSTANCES
|
||||
|
@ -78,8 +78,8 @@ define GPS_MOVING_BASELINE 0
|
||||
define HAL_ADSB_SAGETECH_ENABLED 0
|
||||
define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED 0
|
||||
define AP_AIS_ENABLED 0
|
||||
define HAL_BATTMON_INA2XX_ENABLED 0
|
||||
define AP_BATTMON_SMBUS_ENABLE 0
|
||||
define AP_BATTERY_BACKEND_DEFAULT_ENABLED 0
|
||||
define AP_BATTERY_ANALOG_ENABLED 1
|
||||
define HAL_CRSF_TELEM_ENABLED 0
|
||||
define HAL_EFI_ENABLED 0
|
||||
define HAL_EXTERNAL_AHRS_ENABLED 0
|
||||
|
@ -148,4 +148,4 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
# minimal drivers to reduce flash usage
|
||||
include ../include/minimal.inc
|
||||
define AP_BATTMON_SYNTHETIC_CURRENT_ENABLED 0
|
||||
define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 0
|
||||
|
@ -155,4 +155,4 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
||||
|
||||
# minimal drivers to reduce flash usage
|
||||
include ../include/minimal.inc
|
||||
define AP_BATTMON_SYNTHETIC_CURRENT_ENABLED 0
|
||||
define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 0
|
||||
|
Loading…
Reference in New Issue
Block a user