mirror of https://github.com/ArduPilot/ardupilot
HAL_PX4: added storage performance counters
This commit is contained in:
parent
fc8065b50f
commit
0e79b93289
|
@ -168,6 +168,7 @@ void PX4Storage::_timer_tick(void)
|
|||
if (_fd == -1 || _dirty_mask == 0) {
|
||||
return;
|
||||
}
|
||||
perf_begin(_perf_storage);
|
||||
// write out the first dirty set of lines. We don't write more
|
||||
// than one to keep the latency of this call to a minimum
|
||||
uint8_t i, n;
|
||||
|
@ -177,6 +178,9 @@ void PX4Storage::_timer_tick(void)
|
|||
}
|
||||
}
|
||||
if (i == PX4_STORAGE_NUM_LINES) {
|
||||
// this shouldn't be possible
|
||||
perf_end(_perf_storage);
|
||||
perf_count(_perf_errors);
|
||||
return;
|
||||
}
|
||||
uint32_t write_mask = (1U<<i);
|
||||
|
@ -201,11 +205,15 @@ void PX4Storage::_timer_tick(void)
|
|||
if (write(_fd, &_buffer[i<<PX4_STORAGE_LINE_SHIFT], n<<PX4_STORAGE_LINE_SHIFT) != n<<PX4_STORAGE_LINE_SHIFT) {
|
||||
// write error - likely EINTR
|
||||
_dirty_mask |= write_mask;
|
||||
perf_count(_perf_errors);
|
||||
}
|
||||
if (_dirty_mask == 0) {
|
||||
fsync(_fd);
|
||||
if (fsync(_fd) != 0) {
|
||||
perf_count(_perf_errors);
|
||||
}
|
||||
}
|
||||
}
|
||||
perf_end(_perf_storage);
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
|
||||
#include <AP_HAL.h>
|
||||
#include "AP_HAL_PX4_Namespace.h"
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
#define PX4_STORAGE_SIZE 4096
|
||||
#define PX4_STORAGE_MAX_WRITE 512
|
||||
|
@ -14,9 +15,12 @@
|
|||
|
||||
class PX4::PX4Storage : public AP_HAL::Storage {
|
||||
public:
|
||||
PX4Storage() {
|
||||
_fd = -1;
|
||||
}
|
||||
PX4Storage() :
|
||||
_fd(-1),
|
||||
_dirty_mask(0),
|
||||
_perf_storage(perf_alloc(PC_ELAPSED, "APM_storage")),
|
||||
_perf_errors(perf_alloc(PC_COUNT, "APM_storage_errors"))
|
||||
{}
|
||||
void init(void* machtnichts) {}
|
||||
uint8_t read_byte(uint16_t loc);
|
||||
uint16_t read_word(uint16_t loc);
|
||||
|
@ -37,6 +41,8 @@ private:
|
|||
void _mark_dirty(uint16_t loc, uint16_t length);
|
||||
uint8_t _buffer[PX4_STORAGE_SIZE];
|
||||
volatile uint32_t _dirty_mask;
|
||||
perf_counter_t _perf_storage;
|
||||
perf_counter_t _perf_errors;
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_PX4_STORAGE_H__
|
||||
|
|
Loading…
Reference in New Issue