mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL: Add simple stress test for RingBuffer class
It runs a Producer/Consumer thread pair endless reading and writing a ByteBuffer. Producer writes a number sequence that is twice the ByteBuffer size so a given position have a different data on each write pass. Consumer makes sure that this pattern is not broken and aborts the program if it is. It is possible to spawn more pairs by informing a number as argument of the program.
This commit is contained in:
parent
dbd074b250
commit
641671a366
92
libraries/AP_HAL/examples/RingBuffer/stress_RingBuffer.cpp
Normal file
92
libraries/AP_HAL/examples/RingBuffer/stress_RingBuffer.cpp
Normal file
@ -0,0 +1,92 @@
|
||||
// g++ stress_RingBuffer.cpp ../../utility/RingBuffer.cpp -I../../utility -pthread -o stress_ring && ./stress_ring
|
||||
|
||||
#include <condition_variable>
|
||||
#include <iostream>
|
||||
#include <mutex>
|
||||
#include <thread>
|
||||
|
||||
#include "RingBuffer.h"
|
||||
|
||||
using namespace std;
|
||||
|
||||
struct stress_pairs {
|
||||
uint8_t pair_id;
|
||||
uint8_t reader_buf[32];
|
||||
ByteBuffer buf{128};
|
||||
thread consumer;
|
||||
thread producer;
|
||||
};
|
||||
|
||||
//This buffer is shared among producers.
|
||||
static uint8_t writer_buf[256];
|
||||
|
||||
mutex error_mtx;
|
||||
condition_variable error_cond;
|
||||
|
||||
static void consumer_thread(struct stress_pairs *pair) {
|
||||
uint32_t ret;
|
||||
uint8_t last = 0;
|
||||
|
||||
for (;;) {
|
||||
ret = pair->buf.read(pair->reader_buf, sizeof(pair->reader_buf));
|
||||
|
||||
for (uint32_t i = 0; i < ret; i++) {
|
||||
if (pair->reader_buf[i] != last) {
|
||||
fprintf(stderr, "[id=%u read=%u] Expected=%u Got=%u\n",
|
||||
pair->pair_id, ret, last, pair->reader_buf[i]);
|
||||
unique_lock<mutex> lck(error_mtx);
|
||||
error_cond.notify_all();
|
||||
}
|
||||
last++;
|
||||
last %= sizeof(writer_buf);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void producer_thread(struct stress_pairs *pair) {
|
||||
uint8_t next = 0;
|
||||
|
||||
for (;;) {
|
||||
// Overflow will do the magic
|
||||
next += pair->buf.write(writer_buf + next, sizeof(writer_buf) - next);
|
||||
next %= sizeof(writer_buf);
|
||||
}
|
||||
}
|
||||
|
||||
static void
|
||||
usage(const char *program)
|
||||
{
|
||||
cout << "Usage: " << program << " [pairs]\n"
|
||||
" pair - number of <producer,consumer> pairs that should be created. [Default=1]\n";
|
||||
}
|
||||
|
||||
int main(int argc, char const **argv) {
|
||||
unsigned int i, pairs = 1;
|
||||
struct stress_pairs *list;
|
||||
|
||||
if (argc > 1 && (!sscanf(argv[1], "%u", &pairs) || !pairs)) {
|
||||
usage(argv[0]);
|
||||
return EXIT_SUCCESS;
|
||||
}
|
||||
|
||||
for (i = 0; i < sizeof(writer_buf); i++)
|
||||
writer_buf[i] = i;
|
||||
|
||||
cout << "Hello Threaded World!\n";
|
||||
unique_lock<mutex> lck(error_mtx);
|
||||
|
||||
list = new struct stress_pairs[pairs];
|
||||
for (i = 0; i < pairs; i++) {
|
||||
cout << "Launching pair "<< i << "... ";
|
||||
list[i].pair_id = i;
|
||||
list[i].consumer = thread(consumer_thread, list + i);
|
||||
list[i].producer = thread(producer_thread, list + i);
|
||||
cout << "done!" << endl;
|
||||
}
|
||||
|
||||
error_cond.wait(lck);
|
||||
|
||||
// Let the OS do all the cleaning
|
||||
cout << "Aborting: Good bye **failure** World!\n";
|
||||
return EXIT_FAILURE;
|
||||
}
|
Loading…
Reference in New Issue
Block a user