HAL_Linux: use ExpandingString
This commit is contained in:
parent
42bc9adfb7
commit
16753a51f4
@ -39,6 +39,8 @@
|
||||
#include <cstring>
|
||||
#include "Scheduler.h"
|
||||
#include <AP_CANManager/AP_CANManager.h>
|
||||
#include <AP_Common/ExpandingString.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace Linux;
|
||||
@ -571,41 +573,36 @@ bool CANIface::CANSocketEventSource::wait(uint64_t duration, AP_HAL::EventHandle
|
||||
return true;
|
||||
}
|
||||
|
||||
uint32_t CANIface::get_stats(char* data, uint32_t max_size)
|
||||
void CANIface::get_stats(ExpandingString &str)
|
||||
{
|
||||
if (data == nullptr) {
|
||||
return 0;
|
||||
}
|
||||
uint32_t ret = snprintf(data, max_size,
|
||||
"tx_requests: %u\n"
|
||||
"tx_write_fail: %u\n"
|
||||
"tx_full: %u\n"
|
||||
"tx_confirmed: %u\n"
|
||||
"tx_success: %u\n"
|
||||
"tx_timedout: %u\n"
|
||||
"rx_received: %u\n"
|
||||
"rx_errors: %u\n"
|
||||
"num_downs: %u\n"
|
||||
"num_rx_poll_req: %u\n"
|
||||
"num_tx_poll_req: %u\n"
|
||||
"num_poll_waits: %u\n"
|
||||
"num_poll_tx_events: %u\n"
|
||||
"num_poll_rx_events: %u\n",
|
||||
stats.tx_requests,
|
||||
stats.tx_write_fail,
|
||||
stats.tx_full,
|
||||
stats.tx_confirmed,
|
||||
stats.tx_success,
|
||||
stats.tx_timedout,
|
||||
stats.rx_received,
|
||||
stats.rx_errors,
|
||||
stats.num_downs,
|
||||
stats.num_rx_poll_req,
|
||||
stats.num_tx_poll_req,
|
||||
stats.num_poll_waits,
|
||||
stats.num_poll_tx_events,
|
||||
stats.num_poll_rx_events);
|
||||
return ret;
|
||||
str.printf("tx_requests: %u\n"
|
||||
"tx_write_fail: %u\n"
|
||||
"tx_full: %u\n"
|
||||
"tx_confirmed: %u\n"
|
||||
"tx_success: %u\n"
|
||||
"tx_timedout: %u\n"
|
||||
"rx_received: %u\n"
|
||||
"rx_errors: %u\n"
|
||||
"num_downs: %u\n"
|
||||
"num_rx_poll_req: %u\n"
|
||||
"num_tx_poll_req: %u\n"
|
||||
"num_poll_waits: %u\n"
|
||||
"num_poll_tx_events: %u\n"
|
||||
"num_poll_rx_events: %u\n",
|
||||
stats.tx_requests,
|
||||
stats.tx_write_fail,
|
||||
stats.tx_full,
|
||||
stats.tx_confirmed,
|
||||
stats.tx_success,
|
||||
stats.tx_timedout,
|
||||
stats.rx_received,
|
||||
stats.rx_errors,
|
||||
stats.num_downs,
|
||||
stats.num_rx_poll_req,
|
||||
stats.num_tx_poll_req,
|
||||
stats.num_poll_waits,
|
||||
stats.num_poll_tx_events,
|
||||
stats.num_poll_rx_events);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -113,7 +113,7 @@ public:
|
||||
|
||||
// fetch stats text and return the size of the same,
|
||||
// results available via @SYS/can0_stats.txt or @SYS/can1_stats.txt
|
||||
uint32_t get_stats(char* data, uint32_t max_size) override;
|
||||
void get_stats(ExpandingString &str) override;
|
||||
|
||||
class CANSocketEventSource : public AP_HAL::EventSource {
|
||||
friend class CANIface;
|
||||
|
Loading…
Reference in New Issue
Block a user