APM:Libraries
RingBuffer.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
4 
5 #include <condition_variable>
6 #include <iostream>
7 #include <mutex>
8 #include <thread>
9 
11 
12 using namespace std;
13 
14 struct stress_pairs {
15  uint8_t pair_id;
16  uint8_t reader_buf[32];
17  ByteBuffer buf{128};
18  thread consumer;
19  thread producer;
20 };
21 
22 //This buffer is shared among producers.
23 static uint8_t writer_buf[256];
24 
25 mutex error_mtx;
26 condition_variable error_cond;
27 
28 static void consumer_thread(struct stress_pairs *pair) {
29  uint32_t ret;
30  uint8_t last = 0;
31 
32  for (;;) {
33  ret = pair->buf.read(pair->reader_buf, sizeof(pair->reader_buf));
34 
35  for (uint32_t i = 0; i < ret; i++) {
36  if (pair->reader_buf[i] != last) {
37  fprintf(stderr, "[id=%u read=%u] Expected=%u Got=%u\n",
38  pair->pair_id, ret, last, pair->reader_buf[i]);
39  unique_lock<mutex> lck(error_mtx);
40  error_cond.notify_all();
41  }
42  last++;
43  last %= sizeof(writer_buf);
44  }
45  }
46 }
47 
48 static void producer_thread(struct stress_pairs *pair) {
49  uint8_t next = 0;
50 
51  for (;;) {
52  // Overflow will do the magic
53  next += pair->buf.write(writer_buf + next, sizeof(writer_buf) - next);
54  next %= sizeof(writer_buf);
55  }
56 }
57 
58 static void
59 usage(const char *program)
60 {
61  cout << "Usage: " << program << " [pairs]\n"
62  " pair - number of <producer,consumer> pairs that should be created. [Default=1]\n";
63 }
64 
65 int main(int argc, char const **argv) {
66  unsigned int i, pairs = 1;
67  struct stress_pairs *list;
68 
69  if (argc > 1 && (!sscanf(argv[1], "%u", &pairs) || !pairs)) {
70  usage(argv[0]);
71  return EXIT_SUCCESS;
72  }
73 
74  for (i = 0; i < sizeof(writer_buf); i++)
75  writer_buf[i] = i;
76 
77  cout << "Hello Threaded World!\n";
78  unique_lock<mutex> lck(error_mtx);
79 
80  list = new struct stress_pairs[pairs];
81  for (i = 0; i < pairs; i++) {
82  cout << "Launching pair "<< i << "... ";
83  list[i].pair_id = i;
84  list[i].consumer = thread(consumer_thread, list + i);
85  list[i].producer = thread(producer_thread, list + i);
86  cout << "done!" << endl;
87  }
88 
89  error_cond.wait(lck);
90 
91  // Let the OS do all the cleaning
92  cout << "Aborting: Good bye **failure** World!\n";
93  return EXIT_FAILURE;
94 }
95 
96 #else
97 
98 #include <stdio.h>
99 
100 const AP_HAL::HAL& hal = AP_HAL::get_HAL();
101 
102 static void loop() { }
103 static void setup()
104 {
105  printf("Board not currently supported\n");
106 }
107 
108 AP_HAL_MAIN();
109 
110 #endif
int printf(const char *fmt,...)
Definition: stdio.c:113
uint8_t pair_id
Definition: RingBuffer.cpp:15
thread producer
Definition: RingBuffer.cpp:19
static void usage(const char *program)
Definition: RingBuffer.cpp:59
static void consumer_thread(struct stress_pairs *pair)
Definition: RingBuffer.cpp:28
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
thread consumer
Definition: RingBuffer.cpp:18
int sscanf(const char *buf, const char *fmt,...)
Definition: stdio.c:136
static void producer_thread(struct stress_pairs *pair)
Definition: RingBuffer.cpp:48
void loop()
Definition: AC_PID_test.cpp:34
condition_variable error_cond
Definition: RingBuffer.cpp:26
uint32_t read(uint8_t *data, uint32_t len)
Definition: RingBuffer.cpp:212
ByteBuffer buf
Definition: RingBuffer.cpp:17
uint8_t reader_buf[32]
Definition: RingBuffer.cpp:16
int main(int argc, char const **argv)
Definition: RingBuffer.cpp:65
const HAL & get_HAL()
uint32_t write(const uint8_t *data, uint32_t len)
Definition: RingBuffer.cpp:79
static uint8_t writer_buf[256]
Definition: RingBuffer.cpp:23
mutex error_mtx
Definition: RingBuffer.cpp:25
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
#define AP_HAL_MAIN()
Definition: AP_HAL_Main.h:29
void setup()
Definition: AC_PID_test.cpp:26