AP_TemperatureSensor: use AP_Enum<>, add sitl, add _config.h

This commit is contained in:
Tom Pittenger 2022-10-11 11:59:59 -07:00 committed by Andrew Tridgell
parent 1205e26ace
commit 475fb67c2b
6 changed files with 82 additions and 77 deletions

View File

@ -19,9 +19,8 @@
#include <AP_Vehicle/AP_Vehicle_Type.h>
#ifndef AP_TEMPERATURE_SENSOR_DUMMY_METHODS_ENABLED
#define AP_TEMPERATURE_SENSOR_DUMMY_METHODS_ENABLED (!APM_BUILD_TYPE(APM_BUILD_ArduSub) && !AP_TEMPERATURE_SENSOR_ENABLED_BY_USER)
#endif
#define AP_TEMPERATURE_SENSOR_DUMMY_METHODS_ENABLED (!(APM_BUILD_TYPE(APM_BUILD_ArduSub) || (AP_TEMPERATURE_SENSOR_ENABLED == 1)))
#if !AP_TEMPERATURE_SENSOR_DUMMY_METHODS_ENABLED
@ -118,7 +117,7 @@ void AP_TemperatureSensor::init()
// For Sub set the Default: Type to TSYS01 and I2C_ADDR of 0x77
#if APM_BUILD_TYPE(APM_BUILD_ArduSub)
AP_Param::set_default_by_name("TEMP1_TYPE", (int8_t)AP_TemperatureSensor::Type::TSYS01);
AP_Param::set_default_by_name("TEMP1_TYPE", (float)AP_TemperatureSensor_Params::Type::TSYS01);
AP_Param::set_default_by_name("TEMP1_ADDR", TSYS01_ADDR_CSB0);
#endif
@ -127,16 +126,16 @@ void AP_TemperatureSensor::init()
switch (get_type(instance)) {
#if AP_TEMPERATURE_SENSOR_TSYS01_ENABLED
case AP_TemperatureSensor::Type::TSYS01:
case AP_TemperatureSensor_Params::Type::TSYS01:
drivers[instance] = new AP_TemperatureSensor_TSYS01(*this, _state[instance], _params[instance]);
break;
#endif
#if AP_TEMPERATURE_SENSOR_MCP9600_ENABLED
case AP_TemperatureSensor::Type::MCP9600:
case AP_TemperatureSensor_Params::Type::MCP9600:
drivers[instance] = new AP_TemperatureSensor_MCP9600(*this, _state[instance], _params[instance]);
break;
#endif
case AP_TemperatureSensor::Type::NONE:
case AP_TemperatureSensor_Params::Type::NONE:
default:
break;
}
@ -158,7 +157,7 @@ void AP_TemperatureSensor::init()
void AP_TemperatureSensor::update()
{
for (uint8_t i=0; i<_num_instances; i++) {
if (drivers[i] != nullptr && get_type(i) != AP_TemperatureSensor::Type::NONE) {
if (drivers[i] != nullptr && get_type(i) != AP_TemperatureSensor_Params::Type::NONE) {
drivers[i]->update();
#if HAL_LOGGING_ENABLED
@ -171,12 +170,12 @@ void AP_TemperatureSensor::update()
}
}
AP_TemperatureSensor::Type AP_TemperatureSensor::get_type(const uint8_t instance) const
AP_TemperatureSensor_Params::Type AP_TemperatureSensor::get_type(const uint8_t instance) const
{
if (instance >= AP_TEMPERATURE_SENSOR_MAX_INSTANCES) {
return AP_TemperatureSensor::Type::NONE;
return AP_TemperatureSensor_Params::Type::NONE;
}
return (AP_TemperatureSensor::Type)_params[instance].type.get();
return (AP_TemperatureSensor_Params::Type)_params[instance].type.get();
}
// returns true if there is a temperature reading
@ -195,9 +194,9 @@ bool AP_TemperatureSensor::healthy(const uint8_t instance) const
return instance < _num_instances && drivers[instance] != nullptr && drivers[instance]->healthy();
}
AP_TemperatureSensor::Source AP_TemperatureSensor::get_source(const uint8_t instance) const
AP_TemperatureSensor_Params::Source AP_TemperatureSensor::get_source(const uint8_t instance) const
{
return healthy(instance) ? (AP_TemperatureSensor::Source)_params[instance].source.get() : AP_TemperatureSensor::Source::None;
return healthy(instance) ? (AP_TemperatureSensor_Params::Source)_params[instance].source.get() : AP_TemperatureSensor_Params::Source::None;
}
int32_t AP_TemperatureSensor::get_source_id(const uint8_t instance) const
@ -211,8 +210,8 @@ void AP_TemperatureSensor::init() { };
void AP_TemperatureSensor::update() { };
bool AP_TemperatureSensor::get_temperature(float &temp, const uint8_t instance) const { return false; };
bool AP_TemperatureSensor::healthy(const uint8_t instance) const { return false; };
AP_TemperatureSensor::Type AP_TemperatureSensor::get_type(const uint8_t instance) const { return AP_TemperatureSensor::Type::NONE; };
AP_TemperatureSensor::Source AP_TemperatureSensor::get_source(const uint8_t instance) const { return AP_TemperatureSensor::Source::None; };
AP_TemperatureSensor_Params::Type AP_TemperatureSensor::get_type(const uint8_t instance) const { return AP_TemperatureSensor_Params::Type::NONE; };
AP_TemperatureSensor_Params::Source AP_TemperatureSensor::get_source(const uint8_t instance) const { return AP_TemperatureSensor_Params::Source::None; };
int32_t AP_TemperatureSensor::get_source_id(const uint8_t instance) const { return false; };
AP_TemperatureSensor::AP_TemperatureSensor() {}

View File

@ -14,28 +14,12 @@
*/
#pragma once
#include <AP_HAL/AP_HAL.h>
#ifdef AP_TEMPERATURE_SENSOR_ENABLED
#define AP_TEMPERATURE_SENSOR_ENABLED_BY_USER AP_TEMPERATURE_SENSOR_ENABLED
#else
#define AP_TEMPERATURE_SENSOR_ENABLED_BY_USER 0
#define AP_TEMPERATURE_SENSOR_ENABLED (!HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024)
#endif
#include "AP_TemperatureSensor_config.h"
#if AP_TEMPERATURE_SENSOR_ENABLED
#include "AP_TemperatureSensor_Params.h"
// 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
// declare backend class
class AP_TemperatureSensor_Backend;
class AP_TemperatureSensor_TSYS01;
@ -56,30 +40,6 @@ public:
static AP_TemperatureSensor *get_singleton() { return _singleton; }
// temperature sensor types
enum class Type : uint8_t {
NONE = 0,
TSYS01 = 1,
MCP9600 = 2,
};
// option to map to another system component
enum class Source : uint8_t {
None = 0,
ESC = 1,
Motor = 2,
Battery_Index = 3,
Battery_ID_SerialNumber = 4,
};
// The TemperatureSensor_State structure is filled in by the backend driver
struct TemperatureSensor_State {
const struct AP_Param::GroupInfo *var_info;
uint32_t last_time_ms; // time when the sensor was last read in milliseconds
float temperature; // temperature (deg C)
uint8_t instance; // instance number
};
// Return the number of temperature sensors instances
uint8_t num_instances(void) const { return _num_instances; }
@ -94,8 +54,8 @@ public:
bool healthy(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const;
// accessors to params
Type get_type(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const;
Source get_source(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const;
AP_TemperatureSensor_Params::Type get_type(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const;
AP_TemperatureSensor_Params::Source get_source(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const;
int32_t get_source_id(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const;
static const struct AP_Param::GroupInfo var_info[];
@ -107,6 +67,14 @@ protected:
private:
static AP_TemperatureSensor *_singleton;
// The TemperatureSensor_State structure is filled in by the backend driver
struct TemperatureSensor_State {
const struct AP_Param::GroupInfo *var_info;
uint32_t last_time_ms; // time when the sensor was last read in milliseconds
float temperature; // temperature (deg C)
uint8_t instance; // instance number
};
TemperatureSensor_State _state[AP_TEMPERATURE_SENSOR_MAX_INSTANCES];
AP_TemperatureSensor_Backend *drivers[AP_TEMPERATURE_SENSOR_MAX_INSTANCES];

View File

@ -67,29 +67,29 @@ void AP_TemperatureSensor_Backend::update_external_libraries(const float tempera
AP_ESC_Telem_Backend::TelemetryData t;
#endif
switch ((AP_TemperatureSensor::Source)_params.source.get()) {
switch ((AP_TemperatureSensor_Params::Source)_params.source.get()) {
#if HAL_WITH_ESC_TELEM
case AP_TemperatureSensor::Source::ESC:
case AP_TemperatureSensor_Params::Source::ESC:
t.temperature_cdeg = temperature * 100;
update_telem_data(_params.source_id-1, t, AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE_EXTERNAL);
break;
case AP_TemperatureSensor::Source::Motor:
case AP_TemperatureSensor_Params::Source::Motor:
t.motor_temp_cdeg = temperature * 100;
update_telem_data(_params.source_id-1, t, AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE_EXTERNAL);
break;
#endif
#if !defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BATTERY)
case AP_TemperatureSensor::Source::Battery_Index:
case AP_TemperatureSensor_Params::Source::Battery_Index:
AP::battery().set_temperature(temperature, _params.source_id-1);
break;
case AP_TemperatureSensor::Source::Battery_ID_SerialNumber:
case AP_TemperatureSensor_Params::Source::Battery_ID_SerialNumber:
AP::battery().set_temperature_by_serial_number(temperature, _params.source_id);
break;
#endif
case AP_TemperatureSensor::Source::None:
case AP_TemperatureSensor_Params::Source::None:
default:
break;
}

View File

@ -18,10 +18,6 @@
#if AP_TEMPERATURE_SENSOR_ENABLED
#ifndef AP_TEMPERATURE_SENSOR_TYPE_DEFAULT
#define AP_TEMPERATURE_SENSOR_TYPE_DEFAULT 0
#endif
#ifndef AP_TEMPERATURE_SENSOR_I2C_ADDR_DEFAULT
#define AP_TEMPERATURE_SENSOR_I2C_ADDR_DEFAULT 0
#endif
@ -34,10 +30,6 @@
#define AP_TEMPERATURE_SENSOR_SOURCE_ID_DEFAULT -1
#endif
#ifndef AP_TEMPERATURE_SENSOR_SOURCE_DEFAULT
#define AP_TEMPERATURE_SENSOR_SOURCE_DEFAULT (int8_t)AP_TemperatureSensor::Source::None
#endif
const AP_Param::GroupInfo AP_TemperatureSensor_Params::var_info[] = {
// @Param: TYPE
// @DisplayName: Temperature Sensor Type
@ -45,7 +37,7 @@ const AP_Param::GroupInfo AP_TemperatureSensor_Params::var_info[] = {
// @Values: 0:Disabled, 1:TSYS01, 2:MCP9600
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO_FLAGS("TYPE", 1, AP_TemperatureSensor_Params, type, AP_TEMPERATURE_SENSOR_TYPE_DEFAULT, AP_PARAM_FLAG_ENABLE),
AP_GROUPINFO_FLAGS("TYPE", 1, AP_TemperatureSensor_Params, type, (float)Type::NONE, AP_PARAM_FLAG_ENABLE),
// @Param: BUS
// @DisplayName: Temperature sensor bus
@ -68,7 +60,7 @@ const AP_Param::GroupInfo AP_TemperatureSensor_Params::var_info[] = {
// @Description: Sensor Source is used to match up the source of the temperature data and populate the appropriate system-component. If 0 (None) then the data is only available via log.
// @Values: 0: None, 1:ESC, 2:Motor, 3:Battery Index, 4:Battery ID/SerialNumber
// @User: Standard
AP_GROUPINFO("SRC", 4, AP_TemperatureSensor_Params, source, AP_TEMPERATURE_SENSOR_SOURCE_DEFAULT),
AP_GROUPINFO("SRC", 4, AP_TemperatureSensor_Params, source, (float)Source::None),
// @Param: SRC_ID
// @DisplayName: Sensor Source Identification

View File

@ -25,10 +25,26 @@ public:
CLASS_NO_COPY(AP_TemperatureSensor_Params);
AP_Int8 type; // AP_TemperatureSensor::Type, 0=disabled, others see frontend enum TYPE
// temperature sensor types
enum class Type : uint8_t {
NONE = 0,
TSYS01 = 1,
MCP9600 = 2,
};
// option to map to another system component
enum class Source : uint8_t {
None = 0,
ESC = 1,
Motor = 2,
Battery_Index = 3,
Battery_ID_SerialNumber = 4,
};
AP_Enum<Type> type; // 0=disabled, others see frontend enum TYPE
AP_Int8 bus; // I2C bus number
AP_Int8 bus_address; // I2C address
AP_Int8 source; // AP_TemperatureSensor::Source, library mapping
AP_Enum<Source> source; // library mapping
AP_Int32 source_id; // library instance mapping
};

View File

@ -0,0 +1,30 @@
#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_MINIMIZE_FEATURES || BOARD_FLASH_SIZE <= 1024
#define AP_TEMPERATURE_SENSOR_ENABLED 0
#elif (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#define AP_TEMPERATURE_SENSOR_ENABLED 1
#else
#define AP_TEMPERATURE_SENSOR_ENABLED 2
#endif
#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