mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_UAVAN: pass error_count from ESC Status packet to AP_ESC_Telem
This commit is contained in:
parent
c5c7863829
commit
1d57ada441
@ -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)
|
||||
|
Loading…
Reference in New Issue
Block a user