mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_TemperatureSensor: support var pointer backend params
This commit is contained in:
parent
748dd22f4e
commit
53948b1070
@ -51,53 +51,95 @@ const AP_Param::GroupInfo AP_TemperatureSensor::var_info[] = {
|
||||
// @Path: AP_TemperatureSensor_Params.cpp
|
||||
AP_SUBGROUPINFO(_params[0], "1_", 10, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||
|
||||
// @Group: 1_
|
||||
// @Path: AP_TemperatureSensor_Analog.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[0], "1_", 19, AP_TemperatureSensor, backend_var_info[0]),
|
||||
|
||||
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 2
|
||||
// @Group: 2_
|
||||
// @Path: AP_TemperatureSensor_Params.cpp
|
||||
AP_SUBGROUPINFO(_params[1], "2_", 11, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||
|
||||
// @Group: 2_
|
||||
// @Path: AP_TemperatureSensor_Analog.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[1], "2_", 20, AP_TemperatureSensor, backend_var_info[1]),
|
||||
#endif
|
||||
|
||||
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 3
|
||||
// @Group: 3_
|
||||
// @Path: AP_TemperatureSensor_Params.cpp
|
||||
AP_SUBGROUPINFO(_params[2], "3_", 12, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||
|
||||
// @Group: 3_
|
||||
// @Path: AP_TemperatureSensor_Analog.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[2], "3_", 21, AP_TemperatureSensor, backend_var_info[2]),
|
||||
#endif
|
||||
|
||||
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 4
|
||||
// @Group: 4_
|
||||
// @Path: AP_TemperatureSensor_Params.cpp
|
||||
AP_SUBGROUPINFO(_params[3], "4_", 13, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||
|
||||
// @Group: 4_
|
||||
// @Path: AP_TemperatureSensor_Analog.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[3], "4_", 22, AP_TemperatureSensor, backend_var_info[3]),
|
||||
#endif
|
||||
|
||||
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 5
|
||||
// @Group: 5_
|
||||
// @Path: AP_TemperatureSensor_Params.cpp
|
||||
AP_SUBGROUPINFO(_params[4], "5_", 14, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||
|
||||
// @Group: 5_
|
||||
// @Path: AP_TemperatureSensor_Analog.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[4], "5_", 23, AP_TemperatureSensor, backend_var_info[4]),
|
||||
#endif
|
||||
|
||||
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 6
|
||||
// @Group: 6_
|
||||
// @Path: AP_TemperatureSensor_Params.cpp
|
||||
AP_SUBGROUPINFO(_params[5], "6_", 15, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||
|
||||
// @Group: 6_
|
||||
// @Path: AP_TemperatureSensor_Analog.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[5], "6_", 24, AP_TemperatureSensor, backend_var_info[5]),
|
||||
#endif
|
||||
|
||||
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 7
|
||||
// @Group: 7_
|
||||
// @Path: AP_TemperatureSensor_Params.cpp
|
||||
AP_SUBGROUPINFO(_params[6], "7_", 16, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||
|
||||
// @Group: 7_
|
||||
// @Path: AP_TemperatureSensor_Analog.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[6], "7_", 25, AP_TemperatureSensor, backend_var_info[6]),
|
||||
#endif
|
||||
|
||||
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 8
|
||||
// @Group: 8_
|
||||
// @Path: AP_TemperatureSensor_Params.cpp
|
||||
AP_SUBGROUPINFO(_params[7], "8_", 17, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||
|
||||
// @Group: 8_
|
||||
// @Path: AP_TemperatureSensor_Analog.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[7], "8_", 26, AP_TemperatureSensor, backend_var_info[7]),
|
||||
#endif
|
||||
|
||||
#if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 9
|
||||
// @Group: 9_
|
||||
// @Path: AP_TemperatureSensor_Params.cpp
|
||||
AP_SUBGROUPINFO(_params[8], "9_", 18, AP_TemperatureSensor, AP_TemperatureSensor_Params),
|
||||
|
||||
// @Group: 9_
|
||||
// @Path: AP_TemperatureSensor_Analog.cpp
|
||||
AP_SUBGROUPVARPTR(drivers[8], "9_", 26, AP_TemperatureSensor, backend_var_info[8]),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
const AP_Param::GroupInfo *AP_TemperatureSensor::backend_var_info[AP_TEMPERATURE_SENSOR_MAX_INSTANCES];
|
||||
|
||||
// Default Constructor
|
||||
AP_TemperatureSensor::AP_TemperatureSensor()
|
||||
{
|
||||
@ -155,6 +197,12 @@ void AP_TemperatureSensor::init()
|
||||
|
||||
// call init function for each backend
|
||||
if (drivers[instance] != nullptr) {
|
||||
if (_state[instance].var_info != nullptr) {
|
||||
// Load backend specific params
|
||||
backend_var_info[instance] = _state[instance].var_info;
|
||||
AP_Param::load_object_from_eeprom(drivers[instance], backend_var_info[instance]);
|
||||
}
|
||||
|
||||
drivers[instance]->init();
|
||||
// _num_instances is actually the index for looping over instances
|
||||
// the user may have TEMP_TYPE=0 and TEMP2_TYPE=7, in which case
|
||||
|
@ -63,6 +63,7 @@ public:
|
||||
int32_t get_source_id(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const;
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
static const struct AP_Param::GroupInfo *backend_var_info[AP_TEMPERATURE_SENSOR_MAX_INSTANCES];
|
||||
|
||||
protected:
|
||||
// parameters
|
||||
@ -76,6 +77,7 @@ private:
|
||||
uint32_t last_time_ms; // time when the sensor was last read in milliseconds
|
||||
float temperature; // temperature (deg C)
|
||||
uint8_t instance; // instance number
|
||||
const struct AP_Param::GroupInfo *var_info;
|
||||
};
|
||||
|
||||
TemperatureSensor_State _state[AP_TEMPERATURE_SENSOR_MAX_INSTANCES];
|
||||
|
Loading…
Reference in New Issue
Block a user