Scheduler_test.cpp 2.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107
  1. //
  2. // Simple test for the AP_Scheduler interface
  3. //
  4. #include <AP_HAL/AP_HAL.h>
  5. #include <AP_InertialSensor/AP_InertialSensor.h>
  6. #include <AP_Scheduler/AP_Scheduler.h>
  7. #include <AP_BoardConfig/AP_BoardConfig.h>
  8. #include <AP_Logger/AP_Logger.h>
  9. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  10. AP_Int32 log_bitmask;
  11. AP_Logger AP_Logger{log_bitmask};
  12. class SchedTest {
  13. public:
  14. void setup();
  15. void loop();
  16. private:
  17. AP_InertialSensor ins;
  18. AP_Scheduler scheduler{nullptr};
  19. uint32_t ins_counter;
  20. static const AP_Scheduler::Task scheduler_tasks[];
  21. void ins_update(void);
  22. void one_hz_print(void);
  23. void five_second_call(void);
  24. };
  25. static AP_BoardConfig board_config;
  26. static SchedTest schedtest;
  27. #define SCHED_TASK(func, _interval_ticks, _max_time_micros) SCHED_TASK_CLASS(SchedTest, &schedtest, func, _interval_ticks, _max_time_micros)
  28. /*
  29. scheduler table - all regular tasks are listed here, along with how
  30. often they should be called (in 20ms units) and the maximum time
  31. they are expected to take (in microseconds)
  32. */
  33. const AP_Scheduler::Task SchedTest::scheduler_tasks[] = {
  34. SCHED_TASK(ins_update, 50, 1000),
  35. SCHED_TASK(one_hz_print, 1, 1000),
  36. SCHED_TASK(five_second_call, 0.2, 1800),
  37. };
  38. void SchedTest::setup(void)
  39. {
  40. board_config.init();
  41. ins.init(scheduler.get_loop_rate_hz());
  42. // initialise the scheduler
  43. scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks), (uint32_t)-1);
  44. }
  45. void SchedTest::loop(void)
  46. {
  47. // run all tasks
  48. scheduler.loop();
  49. }
  50. /*
  51. update inertial sensor, reading data
  52. */
  53. void SchedTest::ins_update(void)
  54. {
  55. ins_counter++;
  56. ins.update();
  57. }
  58. /*
  59. print something once a second
  60. */
  61. void SchedTest::one_hz_print(void)
  62. {
  63. hal.console->printf("one_hz: t=%lu\n", (unsigned long)AP_HAL::millis());
  64. }
  65. /*
  66. print something every 5 seconds
  67. */
  68. void SchedTest::five_second_call(void)
  69. {
  70. hal.console->printf("five_seconds: t=%lu ins_counter=%u\n", (unsigned long)AP_HAL::millis(), (unsigned)ins_counter);
  71. }
  72. /*
  73. compatibility with old pde style build
  74. */
  75. void setup(void);
  76. void loop(void);
  77. void setup(void)
  78. {
  79. schedtest.setup();
  80. }
  81. void loop(void)
  82. {
  83. schedtest.loop();
  84. }
  85. AP_HAL_MAIN();