diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index 4cebfa68fe..48bd7ec475 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -76,8 +76,8 @@ uint8_t AP_ESC_Telem::get_motor_frequencies_hz(uint8_t nfreqs, float* freqs) con // get mask of ESCs that sent valid telemetry data in the last // ESC_TELEM_DATA_TIMEOUT_MS -uint16_t AP_ESC_Telem::get_active_esc_mask() const { - uint16_t ret = 0; +uint32_t AP_ESC_Telem::get_active_esc_mask() const { + uint32_t ret = 0; const uint32_t now = AP_HAL::millis(); for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { if (now - _telem_data[i].last_update_ms >= ESC_TELEM_DATA_TIMEOUT_MS) { @@ -94,7 +94,7 @@ uint16_t AP_ESC_Telem::get_active_esc_mask() const { // return number of active ESCs present uint8_t AP_ESC_Telem::get_num_active_escs() const { - uint16_t active = get_active_esc_mask(); + uint32_t active = get_active_esc_mask(); return __builtin_popcount(active); } diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.h b/libraries/AP_ESC_Telem/AP_ESC_Telem.h index 04726c1d0a..57037621d7 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.h @@ -68,7 +68,7 @@ public: // get mask of ESCs that sent valid telemetry data in the last // ESC_TELEM_DATA_TIMEOUT_MS - uint16_t get_active_esc_mask() const; + uint32_t get_active_esc_mask() const; // return the last time telemetry data was received in ms for the given ESC or 0 if never uint32_t get_last_telem_data_ms(uint8_t esc_index) const {