mirror of https://github.com/ArduPilot/ardupilot
AP_TemperatureSensor: refactor for upcoming upgrades
This commit is contained in:
parent
9ed192a371
commit
e398579277
|
@ -188,6 +188,16 @@ 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
|
||||
{
|
||||
return healthy(instance) ? (AP_TemperatureSensor::Source)_params[instance].source.get() : AP_TemperatureSensor::Source::None;
|
||||
}
|
||||
|
||||
int32_t AP_TemperatureSensor::get_source_id(const uint8_t instance) const
|
||||
{
|
||||
return healthy(instance) ? _params[instance].source_id.get() : 0;
|
||||
}
|
||||
|
||||
namespace AP {
|
||||
AP_TemperatureSensor &temperature_sensor() {
|
||||
return *AP_TemperatureSensor::get_singleton();
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
#include "AP_TemperatureSensor_Backend.h"
|
||||
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||
|
||||
/*
|
||||
base class constructor.
|
||||
|
@ -56,6 +57,43 @@ void AP_TemperatureSensor_Backend::set_temperature(const float temperature)
|
|||
_state.temperature = temperature;
|
||||
_state.last_time_ms = AP_HAL::millis();
|
||||
}
|
||||
|
||||
update_external_libraries(temperature);
|
||||
}
|
||||
|
||||
void AP_TemperatureSensor_Backend::update_external_libraries(const float temperature)
|
||||
{
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
AP_ESC_Telem_Backend::TelemetryData t;
|
||||
#endif
|
||||
|
||||
switch ((AP_TemperatureSensor::Source)_params.source.get()) {
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
case AP_TemperatureSensor::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:
|
||||
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:
|
||||
AP::battery().set_temperature(temperature, _params.source_id-1);
|
||||
break;
|
||||
case AP_TemperatureSensor::Source::Battery_ID_SerialNumber:
|
||||
AP::battery().set_temperature_by_serial_number(temperature, _params.source_id);
|
||||
break;
|
||||
#endif
|
||||
|
||||
case AP_TemperatureSensor::Source::None:
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#endif // AP_TEMPERATURE_SENSOR_ENABLED
|
||||
|
|
|
@ -18,8 +18,12 @@
|
|||
|
||||
#if AP_TEMPERATURE_SENSOR_ENABLED
|
||||
#include <AP_HAL/Semaphores.h>
|
||||
#include <AP_ESC_Telem/AP_ESC_Telem.h>
|
||||
|
||||
class AP_TemperatureSensor_Backend
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
: public AP_ESC_Telem_Backend
|
||||
#endif
|
||||
{
|
||||
public:
|
||||
// constructor. This incorporates initialisation as well.
|
||||
|
@ -43,6 +47,7 @@ public:
|
|||
protected:
|
||||
|
||||
void set_temperature(const float temperature);
|
||||
void update_external_libraries(const float temperature);
|
||||
|
||||
AP_TemperatureSensor &_front; // reference to front-end
|
||||
AP_TemperatureSensor::TemperatureSensor_State &_state; // reference to this instance's state (held in the front-end)
|
||||
|
|
|
@ -63,6 +63,18 @@ const AP_Param::GroupInfo AP_TemperatureSensor_Params::var_info[] = {
|
|||
// @RebootRequired: True
|
||||
AP_GROUPINFO("ADDR", 3, AP_TemperatureSensor_Params, bus_address, AP_TEMPERATURE_SENSOR_I2C_ADDR_DEFAULT),
|
||||
|
||||
// @Param: SRC
|
||||
// @DisplayName: Sensor Source
|
||||
// @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),
|
||||
|
||||
// @Param: SRC_ID
|
||||
// @DisplayName: Sensor Source Identification
|
||||
// @Description: Sensor Source Identification is used to populate a specific instance of a system component. Examples: TEMP_SRC = 1 (ESC), TEMP_SRC_INDEX = 1 will set the temp of ESC1. TEMP_SRC = 3 (BatteryIndex),TEMP_SRC_INDEX=2 will set the temp of BATT2. TEMP_SRC = 4 (BatteryId?SerialNum),TEMP_SRC_INDEX=42 will set the temp of all batteries that have param BATTn_SERIAL = 42.
|
||||
AP_GROUPINFO("SRC_ID", 5, AP_TemperatureSensor_Params, source_id, AP_TEMPERATURE_SENSOR_SOURCE_ID_DEFAULT),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -29,4 +29,6 @@ public:
|
|||
AP_Int8 bus; // I2C bus number
|
||||
AP_Int8 bus_address; // I2C address
|
||||
|
||||
AP_Int8 source; // AP_TemperatureSensor::Source, library mapping
|
||||
AP_Int32 source_id; // library instance mapping
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue