Skip to content

Commit

Permalink
AP_ESC_Telem: fix RPM timeout race
Browse files Browse the repository at this point in the history
The RPM telemetry data structure can get updated by another thread at
any time. This can cause (now - last_update_us) to be negative, which
looks like the data is nearly UINT32_MAX microseconds stale. To fix
this, we need to use signed integers for the time difference. The
data_valid flag prevents us from accidentally counting extremely stale
data as valid when the signed time difference wraps around, so this
is safe.
  • Loading branch information
robertlong13 committed Jan 2, 2025
1 parent e1fd90b commit 6a3a2b4
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 7 deletions.
12 changes: 7 additions & 5 deletions libraries/AP_ESC_Telem/AP_ESC_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@

//#define ESC_TELEM_DEBUG

#define ESC_RPM_CHECK_TIMEOUT_US 210000UL // timeout for motor running validity
#define ESC_RPM_CHECK_TIMEOUT_US 210000L // timeout for motor running validity

extern const AP_HAL::HAL& hal;

Expand Down Expand Up @@ -202,7 +202,7 @@ bool AP_ESC_Telem::get_rpm(uint8_t esc_index, float& rpm) const

const uint32_t now = AP_HAL::micros();
if (rpm_data_within_timeout(rpmdata, now, ESC_RPM_DATA_TIMEOUT_US)) {
const float slew = MIN(1.0f, (now - rpmdata.last_update_us) * rpmdata.update_rate_hz * (1.0f / 1e6f));
const float slew = constrain_float(int32_t(now - rpmdata.last_update_us) * rpmdata.update_rate_hz * (1.0f / 1e6f), 0, 1);
rpm = (rpmdata.prev_rpm + (rpmdata.rpm - rpmdata.prev_rpm) * slew);

#if AP_SCRIPTING_ENABLED
Expand Down Expand Up @@ -811,16 +811,18 @@ void AP_ESC_Telem::update()
const uint32_t now_us = AP_HAL::micros();
for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {
// Invalidate RPM data if not received for too long
if ((now_us - _rpm_data[i].last_update_us) > ESC_RPM_DATA_TIMEOUT_US) {
// (last_update_us might be fresher than now_us, so we use a signed difference)
if (int32_t(now_us - _rpm_data[i].last_update_us) > ESC_RPM_DATA_TIMEOUT_US) {
_rpm_data[i].data_valid = false;
}
}
}

bool AP_ESC_Telem::rpm_data_within_timeout(const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t now_us, const uint32_t timeout_us)
bool AP_ESC_Telem::rpm_data_within_timeout(const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t now_us, const int32_t timeout_us)
{
// easy case, has the time window been crossed so it's invalid
if ((now_us - instance.last_update_us) > timeout_us) {
// (last_update_us might be fresher than now_us, so we use a signed difference)
if (int32_t(now_us - instance.last_update_us) > timeout_us) {
return false;
}
// we never got a valid data, to it's invalid
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_ESC_Telem/AP_ESC_Telem.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
static_assert(ESC_TELEM_MAX_ESCS > 0, "Cannot have 0 ESC telemetry instances");

#define ESC_TELEM_DATA_TIMEOUT_MS 5000UL
#define ESC_RPM_DATA_TIMEOUT_US 1000000UL
#define ESC_RPM_DATA_TIMEOUT_US 1000000L

class AP_ESC_Telem {
public:
Expand Down Expand Up @@ -134,7 +134,7 @@ class AP_ESC_Telem {
private:

// helper that validates RPM data
static bool rpm_data_within_timeout (const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t now_us, const uint32_t timeout_us);
static bool rpm_data_within_timeout (const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t now_us, const int32_t timeout_us);
static bool was_rpm_data_ever_reported (const volatile AP_ESC_Telem_Backend::RpmData &instance);

#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED
Expand Down

0 comments on commit 6a3a2b4

Please sign in to comment.