|
|
@ -39,6 +39,8 @@ |
|
|
|
#include <cstring> |
|
|
|
#include <cstring> |
|
|
|
#include "Scheduler.h" |
|
|
|
#include "Scheduler.h" |
|
|
|
#include <AP_CANManager/AP_CANManager.h> |
|
|
|
#include <AP_CANManager/AP_CANManager.h> |
|
|
|
|
|
|
|
#include <AP_Common/ExpandingString.h> |
|
|
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
|
|
|
|
|
|
|
|
using namespace HALSITL; |
|
|
|
using namespace HALSITL; |
|
|
@ -576,41 +578,36 @@ bool CANIface::CANSocketEventSource::wait(uint64_t duration, AP_HAL::EventHandle |
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
uint32_t CANIface::get_stats(char* data, uint32_t max_size) |
|
|
|
void CANIface::get_stats(ExpandingString &str) |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (data == nullptr) { |
|
|
|
str.printf("tx_requests: %u\n" |
|
|
|
return 0; |
|
|
|
"tx_write_fail: %u\n" |
|
|
|
} |
|
|
|
"tx_full: %u\n" |
|
|
|
uint32_t ret = snprintf(data, max_size, |
|
|
|
"tx_confirmed: %u\n" |
|
|
|
"tx_requests: %u\n" |
|
|
|
"tx_success: %u\n" |
|
|
|
"tx_write_fail: %u\n" |
|
|
|
"tx_timedout: %u\n" |
|
|
|
"tx_full: %u\n" |
|
|
|
"rx_received: %u\n" |
|
|
|
"tx_confirmed: %u\n" |
|
|
|
"rx_errors: %u\n" |
|
|
|
"tx_success: %u\n" |
|
|
|
"num_downs: %u\n" |
|
|
|
"tx_timedout: %u\n" |
|
|
|
"num_rx_poll_req: %u\n" |
|
|
|
"rx_received: %u\n" |
|
|
|
"num_tx_poll_req: %u\n" |
|
|
|
"rx_errors: %u\n" |
|
|
|
"num_poll_waits: %u\n" |
|
|
|
"num_downs: %u\n" |
|
|
|
"num_poll_tx_events: %u\n" |
|
|
|
"num_rx_poll_req: %u\n" |
|
|
|
"num_poll_rx_events: %u\n", |
|
|
|
"num_tx_poll_req: %u\n" |
|
|
|
stats.tx_requests, |
|
|
|
"num_poll_waits: %u\n" |
|
|
|
stats.tx_write_fail, |
|
|
|
"num_poll_tx_events: %u\n" |
|
|
|
stats.tx_full, |
|
|
|
"num_poll_rx_events: %u\n", |
|
|
|
stats.tx_confirmed, |
|
|
|
stats.tx_requests, |
|
|
|
stats.tx_success, |
|
|
|
stats.tx_write_fail, |
|
|
|
stats.tx_timedout, |
|
|
|
stats.tx_full, |
|
|
|
stats.rx_received, |
|
|
|
stats.tx_confirmed, |
|
|
|
stats.rx_errors, |
|
|
|
stats.tx_success, |
|
|
|
stats.num_downs, |
|
|
|
stats.tx_timedout, |
|
|
|
stats.num_rx_poll_req, |
|
|
|
stats.rx_received, |
|
|
|
stats.num_tx_poll_req, |
|
|
|
stats.rx_errors, |
|
|
|
stats.num_poll_waits, |
|
|
|
stats.num_downs, |
|
|
|
stats.num_poll_tx_events, |
|
|
|
stats.num_rx_poll_req, |
|
|
|
stats.num_poll_rx_events); |
|
|
|
stats.num_tx_poll_req, |
|
|
|
|
|
|
|
stats.num_poll_waits, |
|
|
|
|
|
|
|
stats.num_poll_tx_events, |
|
|
|
|
|
|
|
stats.num_poll_rx_events); |
|
|
|
|
|
|
|
return ret; |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
#endif |
|
|
|
#endif |
|
|
|