AP_Periph: add support for AP_TemperatureSensor

This commit is contained in:
Tom Pittenger 2022-09-02 14:41:38 -07:00 committed by Andrew Tridgell
parent e398579277
commit 3f4755ea7b
6 changed files with 23 additions and 1 deletions

View File

@ -228,6 +228,10 @@ void AP_Periph_FW::init()
}
#endif
#if AP_TEMPERATURE_SENSOR_ENABLED
temperature_sensor.init();
#endif
#ifdef HAL_PERIPH_ENABLE_NOTIFY
notify.init();
#endif
@ -425,6 +429,10 @@ void AP_Periph_FW::update()
#endif
}
#if AP_TEMPERATURE_SENSOR_ENABLED
temperature_sensor.update();
#endif
#if HAL_LOGGING_ENABLED
logger.periodic_tasks();
#endif

View File

@ -14,6 +14,7 @@
#include <AP_EFI/AP_EFI.h>
#include <AP_MSP/AP_MSP.h>
#include <AP_MSP/msp.h>
#include <AP_TemperatureSensor/AP_TemperatureSensor.h>
#include "../AP_Bootloader/app_comms.h"
#include <AP_CheckFirmware/AP_CheckFirmware.h>
#include "hwing_esc.h"
@ -230,6 +231,9 @@ public:
void rcout_handle_safety_state(uint8_t safety_state);
#endif
#if AP_TEMPERATURE_SENSOR_ENABLED
AP_TemperatureSensor temperature_sensor;
#endif
#if defined(HAL_PERIPH_ENABLE_NOTIFY) || defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY)
void update_rainbow();

View File

@ -396,6 +396,12 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
#endif
#endif
#if AP_TEMPERATURE_SENSOR_ENABLED
// @Group: TEMP
// @Path: ../libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp
GOBJECT(temperature_sensor, "TEMP", AP_TemperatureSensor),
#endif
#ifdef HAL_PERIPH_ENABLE_MSP
// @Param: MSP_PORT
// @DisplayName: MSP Serial Port

View File

@ -61,6 +61,7 @@ public:
k_param_efi_baudrate,
k_param_esc_telem_rate,
k_param_can_slcan_cport,
k_param_temperature_sensor,
};
AP_Int16 format_version;

View File

@ -1651,7 +1651,9 @@ void AP_Periph_FW::esc_telem_update()
pkt.current = nan;
}
int16_t temperature;
if (esc_telem.get_temperature(i, temperature)) {
if (esc_telem.get_motor_temperature(i, temperature)) {
pkt.temperature = C_TO_KELVIN(temperature*0.01);
} else if (esc_telem.get_temperature(i, temperature)) {
pkt.temperature = C_TO_KELVIN(temperature*0.01);
} else {
pkt.temperature = nan;

View File

@ -52,6 +52,7 @@ def build(bld):
'AP_Airspeed',
'AP_RangeFinder',
'AP_ROMFS',
'AP_TemperatureSensor',
'AP_MSP',
'SRV_Channel',
'AP_Notify',