RingBuffer.cpp 2.5 KB

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