mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
HAL_PX4: added UART performance counters
This commit is contained in:
parent
6cf1d5e1ff
commit
fc8065b50f
@ -19,9 +19,11 @@ using namespace PX4;
|
|||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
PX4UARTDriver::PX4UARTDriver(const char *devpath) {
|
PX4UARTDriver::PX4UARTDriver(const char *devpath, const char *perf_name) :
|
||||||
_devpath = devpath;
|
_devpath(devpath),
|
||||||
}
|
_perf_uart(perf_alloc(PC_ELAPSED, perf_name))
|
||||||
|
{}
|
||||||
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -316,6 +318,7 @@ void PX4UARTDriver::_timer_tick(void)
|
|||||||
uint16_t _tail;
|
uint16_t _tail;
|
||||||
n = BUF_AVAILABLE(_writebuf);
|
n = BUF_AVAILABLE(_writebuf);
|
||||||
if (n > 0) {
|
if (n > 0) {
|
||||||
|
perf_begin(_perf_uart);
|
||||||
if (_tail > _writebuf_head) {
|
if (_tail > _writebuf_head) {
|
||||||
// do as a single write
|
// do as a single write
|
||||||
int ret = ::write(_fd, &_writebuf[_writebuf_head], n);
|
int ret = ::write(_fd, &_writebuf[_writebuf_head], n);
|
||||||
@ -336,12 +339,14 @@ void PX4UARTDriver::_timer_tick(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
perf_end(_perf_uart);
|
||||||
}
|
}
|
||||||
|
|
||||||
// try to fill the read buffer
|
// try to fill the read buffer
|
||||||
uint16_t _head;
|
uint16_t _head;
|
||||||
n = BUF_SPACE(_readbuf);
|
n = BUF_SPACE(_readbuf);
|
||||||
if (n > 0) {
|
if (n > 0) {
|
||||||
|
perf_begin(_perf_uart);
|
||||||
if (_readbuf_tail < _head) {
|
if (_readbuf_tail < _head) {
|
||||||
// one read will do
|
// one read will do
|
||||||
int ret = ::read(_fd, &_readbuf[_readbuf_tail], n);
|
int ret = ::read(_fd, &_readbuf[_readbuf_tail], n);
|
||||||
@ -361,6 +366,7 @@ void PX4UARTDriver::_timer_tick(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
perf_end(_perf_uart);
|
||||||
}
|
}
|
||||||
|
|
||||||
_in_timer = false;
|
_in_timer = false;
|
||||||
|
@ -3,10 +3,11 @@
|
|||||||
#define __AP_HAL_PX4_UARTDRIVER_H__
|
#define __AP_HAL_PX4_UARTDRIVER_H__
|
||||||
|
|
||||||
#include <AP_HAL_PX4.h>
|
#include <AP_HAL_PX4.h>
|
||||||
|
#include <systemlib/perf_counter.h>
|
||||||
|
|
||||||
class PX4::PX4UARTDriver : public AP_HAL::UARTDriver {
|
class PX4::PX4UARTDriver : public AP_HAL::UARTDriver {
|
||||||
public:
|
public:
|
||||||
PX4UARTDriver(const char *devpath);
|
PX4UARTDriver(const char *devpath, const char *perf_name);
|
||||||
/* PX4 implementations of UARTDriver virtual methods */
|
/* PX4 implementations of UARTDriver virtual methods */
|
||||||
void begin(uint32_t b);
|
void begin(uint32_t b);
|
||||||
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
|
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
|
||||||
@ -65,6 +66,7 @@ private:
|
|||||||
uint16_t _writebuf_size;
|
uint16_t _writebuf_size;
|
||||||
volatile uint16_t _writebuf_head;
|
volatile uint16_t _writebuf_head;
|
||||||
volatile uint16_t _writebuf_tail;
|
volatile uint16_t _writebuf_tail;
|
||||||
|
perf_counter_t _perf_uart;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_HAL_PX4_UARTDRIVER_H__
|
#endif // __AP_HAL_PX4_UARTDRIVER_H__
|
||||||
|
Loading…
Reference in New Issue
Block a user