Skip to content

Commit

Permalink
AP_ESC_Telem: tidy old calls to _telem_data
Browse files Browse the repository at this point in the history
When #27755 was first opened, #26252 had not been merged yet. #26252
refactored a bit, but the change was not applied to #27755. This commit
fixes that.

This should not change the behavior of the code.
  • Loading branch information
robertlong13 committed Sep 10, 2024
1 parent b415d39 commit 9024790
Showing 1 changed file with 7 additions and 7 deletions.
14 changes: 7 additions & 7 deletions libraries/AP_ESC_Telem/AP_ESC_Telem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -565,22 +565,22 @@ void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem

#if AP_EXTENDED_ESC_TELEM_ENABLED
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY) {
_telem_data[esc_index].input_duty = new_data.input_duty;
telemdata.input_duty = new_data.input_duty;
}
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY) {
_telem_data[esc_index].output_duty = new_data.output_duty;
telemdata.output_duty = new_data.output_duty;
}
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::FLAGS) {
_telem_data[esc_index].flags = new_data.flags;
telemdata.flags = new_data.flags;
}
if (data_mask & AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE) {
_telem_data[esc_index].power_percentage = new_data.power_percentage;
telemdata.power_percentage = new_data.power_percentage;
}
#endif //AP_EXTENDED_ESC_TELEM_ENABLED

_telem_data[esc_index].count++;
_telem_data[esc_index].types |= data_mask;
_telem_data[esc_index].last_update_ms = AP_HAL::millis();
telemdata.count++;
telemdata.types |= data_mask;
telemdata.last_update_ms = AP_HAL::millis();
}

// record an update to the RPM together with timestamp, this allows the notch values to be slewed
Expand Down

0 comments on commit 9024790

Please sign in to comment.