APM:Libraries
test_thread.cpp
Go to the documentation of this file.
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 
19 #include <pthread.h>
20 #include <unistd.h>
21 
22 #include <AP_HAL/AP_HAL.h>
23 #include <AP_HAL_Linux/Thread.h>
25 
26 using namespace Linux;
27 
29 
30 class TestThread1 : public Thread {
31 public:
32  TestThread1() : Thread(nullptr) { }
33 
34  int n_loop = 0;
35 
36 protected:
37  bool _run() override {
38  n_loop = 1;
39  return true;
40  }
41 };
42 
43 TEST(LinuxThread, override_run)
44 {
45  TestThread1 thr;
46  EXPECT_TRUE(thr.start(nullptr, 0, 0));
47 
48  while (thr.n_loop == 0) {
49  usleep(10000);
50  }
51 
52  EXPECT_EQ(thr.n_loop, 1);
53 }
54 
55 class TestThread2 : public Thread {
56 public:
58 
59  int n_loop = 0;
60 
61 protected:
62  void _task() {
63  n_loop = 1;
64  }
65 };
66 
67 TEST(LinuxThread, run_task)
68 {
69  TestThread2 thr;
70  EXPECT_TRUE(thr.start(nullptr, 0, 0));
71 
72  while (thr.n_loop == 0) {
73  usleep(10000);
74  }
75 
76  EXPECT_EQ(thr.n_loop, 1);
77 }
78 
79 TEST(LinuxThread, poller_thread)
80 {
81  PollerThread thr;
82  EXPECT_TRUE(thr.start(nullptr, 0, 0));
83 
84  while (!thr.is_started()) {
85  usleep(1000);
86  }
87 
88  usleep(10000);
89 
90  EXPECT_TRUE(thr.stop());
91  EXPECT_TRUE(thr.join());
92 }
93 
95 public:
97 protected:
98  void _task() { }
99 };
100 
101 TEST(LinuxThread, periodic_thread)
102 {
104  EXPECT_TRUE(thr.set_rate(1000));
105  EXPECT_TRUE(thr.start(nullptr, 0, 0));
106 
107  while (!thr.is_started()) {
108  usleep(1000);
109  }
110 
111  // this must fail as the thread already started
112  EXPECT_FALSE(thr.set_rate(10));
113 
114  usleep(10000);
115 
116  EXPECT_TRUE(thr.stop());
117  EXPECT_TRUE(thr.join());
118 }
119 
120 AP_GTEST_MAIN()
bool join()
Definition: Thread.cpp:208
void _task()
Definition: test_thread.cpp:62
bool _run() override
Definition: test_thread.cpp:37
TEST(LinuxThread, override_run)
Definition: test_thread.cpp:43
bool stop() override
bool is_started() const
Definition: Thread.h:42
static const AP_HAL::HAL & hal
Definition: I2CDevice.cpp:61
bool set_rate(uint32_t rate_hz)
Definition: Thread.cpp:225
const HAL & get_HAL()
bool stop() override
Definition: Thread.cpp:274
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
bool start(const char *name, int policy, int prio)
Definition: Thread.cpp:155