APM:Libraries
Thread.h
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 #pragma once
18 
19 #include <pthread.h>
20 #include <inttypes.h>
21 #include <stdlib.h>
22 
23 #include <AP_HAL/utility/functor.h>
24 
25 namespace Linux {
26 
27 /*
28  * Interface abstracting threads
29  */
30 class Thread {
31 public:
32  FUNCTOR_TYPEDEF(task_t, void);
33 
34  Thread(task_t t) : _task(t) { }
35 
36  virtual ~Thread() { }
37 
38  bool start(const char *name, int policy, int prio);
39 
40  bool is_current_thread();
41 
42  bool is_started() const { return _started; }
43 
44  size_t get_stack_usage();
45 
46  bool set_stack_size(size_t stack_size);
47 
48  virtual bool stop() { return false; }
49 
50  bool join();
51 
52 protected:
53  static void *_run_trampoline(void *arg);
54 
55  /*
56  * Run the task assigned in the constructor. May be overriden in case it's
57  * preferred to use Thread as an interface or when user wants to aggregate
58  * some initialization or teardown for the thread.
59  */
60  virtual bool _run();
61 
62  void _poison_stack();
63 
65  bool _started = false;
66  bool _should_exit = false;
67  pthread_t _ctx = 0;
68 
69  struct stack_debug {
70  uint32_t *start;
71  uint32_t *end;
72  } _stack_debug;
73 
74  size_t _stack_size = 0;
75 };
76 
77 class PeriodicThread : public Thread {
78 public:
79  PeriodicThread(Thread::task_t t)
80  : Thread(t)
81  { }
82 
83  bool set_rate(uint32_t rate_hz);
84 
85  bool stop() override;
86 
87 protected:
88  bool _run() override;
89 
90  uint64_t _period_usec = 0;
91 };
92 
93 }
bool join()
Definition: Thread.cpp:208
virtual bool stop()
Definition: Thread.h:48
task_t _task
Definition: Thread.h:64
FUNCTOR_TYPEDEF(task_t, void)
bool _started
Definition: Thread.h:65
virtual bool _run()
Definition: Thread.cpp:46
const char * name
Definition: BusTest.cpp:11
bool is_started() const
Definition: Thread.h:42
PeriodicThread(Thread::task_t t)
Definition: Thread.h:79
void _poison_stack()
Definition: Thread.cpp:76
Thread(task_t t)
Definition: Thread.h:34
virtual ~Thread()
Definition: Thread.h:36
struct Linux::Thread::stack_debug _stack_debug
size_t _stack_size
Definition: Thread.h:74
static void * _run_trampoline(void *arg)
Definition: Thread.cpp:37
bool is_current_thread()
Definition: Thread.cpp:203
bool set_stack_size(size_t stack_size)
Definition: Thread.cpp:236
size_t get_stack_usage()
Definition: Thread.cpp:126
bool start(const char *name, int policy, int prio)
Definition: Thread.cpp:155
bool _should_exit
Definition: Thread.h:66
pthread_t _ctx
Definition: Thread.h:67