From ac2080ff93ae0fee00bb5e8c63db721cb35067e4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 7 Jun 2021 11:02:35 +1000 Subject: [PATCH] AP_ESC_Telem: don't send mavlink msgs if we've never data any data --- libraries/AP_ESC_Telem/AP_ESC_Telem.cpp | 10 ++++++++++ libraries/AP_ESC_Telem/AP_ESC_Telem.h | 2 ++ 2 files changed, 12 insertions(+) diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index 2b54417fc5..edd437a93e 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -195,6 +195,11 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan) { static_assert(ESC_TELEM_MAX_ESCS <= 12, "AP_ESC_Telem::send_esc_telemetry_mavlink() only supports up-to 12 motors"); + if (!_have_data) { + // we've never had any data + return; + } + uint32_t now = AP_HAL::millis(); uint32_t now_us = AP_HAL::micros(); // loop through 3 groups of 4 ESCs @@ -268,6 +273,8 @@ void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem return; } + _have_data = true; + if (data_mask & AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE) { _telem_data[esc_index].temperature_cdeg = new_data.temperature_cdeg; } @@ -299,6 +306,9 @@ void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const uint16_t new_rpm, c if (esc_index > ESC_TELEM_MAX_ESCS) { return; } + + _have_data = true; + const uint32_t now = AP_HAL::micros(); volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[esc_index]; diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.h b/libraries/AP_ESC_Telem/AP_ESC_Telem.h index 402d2939f4..de8afd3a8d 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.h @@ -80,6 +80,8 @@ private: uint32_t _last_telem_log_ms[ESC_TELEM_MAX_ESCS]; uint32_t _last_rpm_log_us[ESC_TELEM_MAX_ESCS]; + bool _have_data; + static AP_ESC_Telem *_singleton; };