AP_UAVAN: pass error_count from ESC Status packet to AP_ESC_Telem

This commit is contained in:
Peter Barker 2023-02-03 09:32:49 +11:00 committed by Andrew Tridgell
parent c5c7863829
commit 1d57ada441

View File

@ -1011,7 +1011,7 @@ void AP_UAVCAN::handle_ESC_status(AP_UAVCAN* ap_uavcan, uint8_t node_id, const E
.current = cb.msg->current,
};
ap_uavcan->update_rpm(esc_index, cb.msg->rpm);
ap_uavcan->update_rpm(esc_index, cb.msg->rpm, cb.msg->error_count);
ap_uavcan->update_telem_data(esc_index, t,
(isnanf(cb.msg->current) ? 0 : AP_ESC_Telem_Backend::TelemetryType::CURRENT)
| (isnanf(cb.msg->voltage) ? 0 : AP_ESC_Telem_Backend::TelemetryType::VOLTAGE)