Skip to content

Commit

Permalink
AP_ESC_Telem: don't send mavlink msgs if we've never data any data
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge authored and peterbarker committed Jun 8, 2021
1 parent 4abf854 commit ac2080f
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 0 deletions.
10 changes: 10 additions & 0 deletions libraries/AP_ESC_Telem/AP_ESC_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
}
Expand Down Expand Up @@ -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];

Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_ESC_Telem/AP_ESC_Telem.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,8 @@ class AP_ESC_Telem {
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;
};

Expand Down

0 comments on commit ac2080f

Please sign in to comment.