mirror of https://github.com/ArduPilot/ardupilot
AP_BattMonitor: create table of used backend paramater indices
Hopefully makes it less likely for conflicts to happen and makes it easier to find free indices.
This commit is contained in:
parent
634e106af4
commit
fb9119fac8
|
@ -84,7 +84,7 @@ const AP_Param::GroupInfo AP_BattMonitor_AD7091R5::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("VLT_OFFSET", 61, AP_BattMonitor_AD7091R5, _volt_offset, 0),
|
||||
|
||||
// Param indexes must be 56 to 61 to avoid conflict with other battery monitor param tables loaded by pointer
|
||||
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
|
@ -55,7 +55,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Analog::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("VLT_OFFSET", 6, AP_BattMonitor_Analog, _volt_offset, 0),
|
||||
|
||||
// Param indexes must be less than 10 to avoid conflict with other battery monitor param tables loaded by pointer
|
||||
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
|
@ -26,6 +26,27 @@
|
|||
#include "AP_ESC_Telem/AP_ESC_Telem.h"
|
||||
#endif
|
||||
|
||||
/*
|
||||
All backends use the same parameter table and set of indices. Therefore, two
|
||||
backends must not use the same index. The list of used indices and
|
||||
corresponding backends is below.
|
||||
|
||||
1-6: AP_BattMonitor_Analog.cpp
|
||||
10-11: AP_BattMonitor_SMBus.cpp
|
||||
20: AP_BattMonitor_Sum.cpp
|
||||
25-26: AP_BattMonitor_INA2xx.cpp
|
||||
27-28: AP_BattMonitor_INA2xx.cpp, AP_BattMonitor_INA239.cpp (legacy duplication)
|
||||
30: AP_BattMonitor_DroneCAN.cpp
|
||||
36: AP_BattMonitor_ESC.cpp
|
||||
40-43: AP_BattMonitor_FuelLevel_Analog.cpp
|
||||
45-48: AP_BattMonitor_FuelLevel_Analog.cpp
|
||||
50-51: AP_BattMonitor_Synthetic_Current.cpp
|
||||
56-58: AP_BattMonitor_INA3221.cpp
|
||||
56-61: AP_BattMonitor_AD7091R5.cpp
|
||||
|
||||
Usage does not need to be contiguous. The maximum possible index is 63.
|
||||
*/
|
||||
|
||||
/*
|
||||
base class constructor.
|
||||
This incorporates initialisation as well.
|
||||
|
|
|
@ -26,7 +26,7 @@ const AP_Param::GroupInfo AP_BattMonitor_DroneCAN::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("CURR_MULT", 30, AP_BattMonitor_DroneCAN, _curr_mult, 1.0),
|
||||
|
||||
// Param indexes must be between 30 and 35 to avoid conflict with other battery monitor param tables loaded by pointer
|
||||
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
|
@ -22,8 +22,6 @@
|
|||
|
||||
const AP_Param::GroupInfo AP_BattMonitor_ESC::var_info[] = {
|
||||
|
||||
// Param indexes must be between 36 and 39 to avoid conflict with other battery monitor param tables loaded by pointer
|
||||
|
||||
// @Param: ESC_MASK
|
||||
// @DisplayName: ESC mask
|
||||
// @Description: If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.
|
||||
|
@ -31,7 +29,7 @@ const AP_Param::GroupInfo AP_BattMonitor_ESC::var_info[] = {
|
|||
// @User: Standard
|
||||
AP_GROUPINFO("ESC_MASK", 36, AP_BattMonitor_ESC, _mask, 0),
|
||||
|
||||
// Param indexes must be between 36 and 39 to avoid conflict with other battery monitor param tables loaded by pointer
|
||||
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
|
@ -58,8 +58,6 @@ const AP_Param::GroupInfo AP_BattMonitor_FuelLevel_Analog::var_info[] = {
|
|||
// @Values: -1:Disabled, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 5:Navigator, 13:Pixhawk2_PM2/CubeOrange_PM2, 14:CubeOrange, 16:Durandal, 100:PX4-v1
|
||||
AP_GROUPINFO("FL_PIN", 43, AP_BattMonitor_FuelLevel_Analog, _pin, -1),
|
||||
|
||||
// index 44 unused and available
|
||||
|
||||
// @Param: FL_FF
|
||||
// @DisplayName: First order term
|
||||
// @Description: First order polynomial fit term
|
||||
|
@ -88,7 +86,7 @@ const AP_Param::GroupInfo AP_BattMonitor_FuelLevel_Analog::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("FL_OFF", 48, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_offset, 0),
|
||||
|
||||
// Param indexes must be between 40 and 49 to avoid conflict with other battery monitor param tables loaded by pointer
|
||||
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
|
@ -47,7 +47,9 @@ const AP_Param::GroupInfo AP_BattMonitor_INA239::var_info[] = {
|
|||
// @Units: Ohm
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SHUNT", 28, AP_BattMonitor_INA239, rShunt, HAL_BATTMON_INA239_SHUNT_RESISTANCE),
|
||||
|
||||
|
||||
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -108,7 +108,9 @@ const AP_Param::GroupInfo AP_BattMonitor_INA2XX::var_info[] = {
|
|||
// @Units: Ohm
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SHUNT", 28, AP_BattMonitor_INA2XX, rShunt, DEFAULT_BATTMON_INA2XX_SHUNT),
|
||||
|
||||
|
||||
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -67,8 +67,6 @@ uint8_t AP_BattMonitor_INA3221::address_driver_count;
|
|||
|
||||
const AP_Param::GroupInfo AP_BattMonitor_INA3221::var_info[] = {
|
||||
|
||||
// Param indexes must be between 56 and 61 to avoid conflict with other battery monitor param tables loaded by pointer
|
||||
|
||||
// @Param: I2C_BUS
|
||||
// @DisplayName: Battery monitor I2C bus number
|
||||
// @Description: Battery monitor I2C bus number
|
||||
|
@ -93,6 +91,8 @@ const AP_Param::GroupInfo AP_BattMonitor_INA3221::var_info[] = {
|
|||
// @RebootRequired: True
|
||||
AP_GROUPINFO("CHANNEL", 58, AP_BattMonitor_INA3221, channel, 1),
|
||||
|
||||
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -10,8 +10,6 @@ extern const AP_HAL::HAL& hal;
|
|||
|
||||
const AP_Param::GroupInfo AP_BattMonitor_SMBus::var_info[] = {
|
||||
|
||||
// Param indexes must be between 10 and 19 to avoid conflict with other battery monitor param tables loaded by pointer
|
||||
|
||||
// @Param: I2C_BUS
|
||||
// @DisplayName: Battery monitor I2C bus number
|
||||
// @Description: Battery monitor I2C bus number
|
||||
|
@ -28,7 +26,7 @@ const AP_Param::GroupInfo AP_BattMonitor_SMBus::var_info[] = {
|
|||
// @RebootRequired: True
|
||||
AP_GROUPINFO("I2C_ADDR", 11, AP_BattMonitor_SMBus, _address, AP_BATTMONITOR_SMBUS_I2C_ADDR),
|
||||
|
||||
// Param indexes must be between 10 and 19 to avoid conflict with other battery monitor param tables loaded by pointer
|
||||
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
|
@ -19,8 +19,6 @@ extern const AP_HAL::HAL& hal;
|
|||
|
||||
const AP_Param::GroupInfo AP_BattMonitor_Sum::var_info[] = {
|
||||
|
||||
// Param indexes must be between 20 and 29 to avoid conflict with other battery monitor param tables loaded by pointer
|
||||
|
||||
// @Param: SUM_MASK
|
||||
// @DisplayName: Battery Sum mask
|
||||
// @Description: 0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.
|
||||
|
@ -28,7 +26,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Sum::var_info[] = {
|
|||
// @User: Standard
|
||||
AP_GROUPINFO("SUM_MASK", 20, AP_BattMonitor_Sum, _sum_mask, 0),
|
||||
|
||||
// Param indexes must be between 20 and 29 to avoid conflict with other battery monitor param tables loaded by pointer
|
||||
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
|
@ -27,7 +27,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Synthetic_Current::var_info[] = {
|
|||
// also inherit analog backend parameters
|
||||
AP_SUBGROUPEXTENSION("", 51, AP_BattMonitor_Synthetic_Current, AP_BattMonitor_Analog::var_info),
|
||||
|
||||
// Param indexes must be between 50 and 55 to avoid conflict with other battery monitor param tables loaded by pointer
|
||||
// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue