AP_ESC_Telem: cleanup whitespace

This commit is contained in:
Maxim Buzdalov 2024-02-20 12:26:24 +00:00 committed by Peter Barker
parent 4e280795b2
commit 5329ab8d92
1 changed files with 4 additions and 4 deletions

View File

@ -312,8 +312,8 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan)
const uint32_t now_us = AP_HAL::micros();
// loop through groups of 4 ESCs
const uint8_t esc_offset = constrain_int16(mavlink_offset, 0, ESC_TELEM_MAX_ESCS-1);
const uint8_t num_idx = ESC_TELEM_MAX_ESCS/4;
const uint8_t esc_offset = constrain_int16(mavlink_offset, 0, ESC_TELEM_MAX_ESCS - 1);
const uint8_t num_idx = ESC_TELEM_MAX_ESCS / 4;
for (uint8_t idx = 0; idx < num_idx; idx++) {
const uint8_t i = (next_idx + idx) % num_idx;
@ -543,7 +543,7 @@ void AP_ESC_Telem::update()
}
}
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 uint32_t timeout_us)
{
// easy case, has the time window been crossed so it's invalid
if ((now_us - instance.last_update_us) > timeout_us) {
@ -557,7 +557,7 @@ bool AP_ESC_Telem::rpm_data_within_timeout (const volatile AP_ESC_Telem_Backend:
return instance.data_valid;
}
bool AP_ESC_Telem::was_rpm_data_ever_reported (const volatile AP_ESC_Telem_Backend::RpmData &instance)
bool AP_ESC_Telem::was_rpm_data_ever_reported(const volatile AP_ESC_Telem_Backend::RpmData &instance)
{
return instance.last_update_us > 0;
}