test_thread.cpp 2.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120
  1. /*
  2. * Copyright (C) 2016 Intel Corporation. All rights reserved.
  3. *
  4. * This file is free software: you can redistribute it and/or modify it
  5. * under the terms of the GNU General Public License as published by the
  6. * Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This file is distributed in the hope that it will be useful, but
  10. * WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  12. * See the GNU General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU General Public License along
  15. * with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. #include <AP_gtest.h>
  18. #include <pthread.h>
  19. #include <unistd.h>
  20. #include <AP_HAL/AP_HAL.h>
  21. #include <AP_HAL_Linux/Thread.h>
  22. #include <AP_HAL_Linux/PollerThread.h>
  23. using namespace Linux;
  24. const AP_HAL::HAL &hal = AP_HAL::get_HAL();
  25. class TestThread1 : public Thread {
  26. public:
  27. TestThread1() : Thread(nullptr) { }
  28. int n_loop = 0;
  29. protected:
  30. bool _run() override {
  31. n_loop = 1;
  32. return true;
  33. }
  34. };
  35. TEST(LinuxThread, override_run)
  36. {
  37. TestThread1 thr;
  38. EXPECT_TRUE(thr.start(nullptr, 0, 0));
  39. while (thr.n_loop == 0) {
  40. usleep(10000);
  41. }
  42. EXPECT_EQ(thr.n_loop, 1);
  43. }
  44. class TestThread2 : public Thread {
  45. public:
  46. TestThread2() : Thread{FUNCTOR_BIND_MEMBER(&TestThread2::_task, void)} { }
  47. int n_loop = 0;
  48. protected:
  49. void _task() {
  50. n_loop = 1;
  51. }
  52. };
  53. TEST(LinuxThread, run_task)
  54. {
  55. TestThread2 thr;
  56. EXPECT_TRUE(thr.start(nullptr, 0, 0));
  57. while (thr.n_loop == 0) {
  58. usleep(10000);
  59. }
  60. EXPECT_EQ(thr.n_loop, 1);
  61. }
  62. TEST(LinuxThread, poller_thread)
  63. {
  64. PollerThread thr;
  65. EXPECT_TRUE(thr.start(nullptr, 0, 0));
  66. while (!thr.is_started()) {
  67. usleep(1000);
  68. }
  69. usleep(10000);
  70. EXPECT_TRUE(thr.stop());
  71. EXPECT_TRUE(thr.join());
  72. }
  73. class TestPeriodicThread1 : public PeriodicThread {
  74. public:
  75. TestPeriodicThread1() : PeriodicThread{FUNCTOR_BIND_MEMBER(&TestPeriodicThread1::_task, void)} { }
  76. protected:
  77. void _task() { }
  78. };
  79. TEST(LinuxThread, periodic_thread)
  80. {
  81. TestPeriodicThread1 thr;
  82. EXPECT_TRUE(thr.set_rate(1000));
  83. EXPECT_TRUE(thr.start(nullptr, 0, 0));
  84. while (!thr.is_started()) {
  85. usleep(1000);
  86. }
  87. // this must fail as the thread already started
  88. EXPECT_FALSE(thr.set_rate(10));
  89. usleep(10000);
  90. EXPECT_TRUE(thr.stop());
  91. EXPECT_TRUE(thr.join());
  92. }
  93. AP_GTEST_MAIN()