APM:Libraries
Device.cpp
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #include "Device.h"
16 
17 #include <arch/board/board.h>
18 #include "board_config.h"
19 #include <stdio.h>
20 #include <AP_HAL/AP_HAL.h>
21 #include <AP_HAL/utility/OwnPtr.h>
22 #include "Scheduler.h"
23 #include "Semaphores.h"
24 
25 extern bool _px4_thread_should_exit;
26 
27 namespace PX4 {
28 
29 static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
30 
31 /*
32  per-bus callback thread
33 */
34 void *DeviceBus::bus_thread(void *arg)
35 {
36  struct DeviceBus *binfo = (struct DeviceBus *)arg;
37 
38  // setup a name for the thread
39  char name[] = "XXX:XX";
40  switch (binfo->hal_device->bus_type()) {
42  snprintf(name, sizeof(name), "I2C:%u",
43  binfo->hal_device->bus_num());
44  break;
45 
47  snprintf(name, sizeof(name), "SPI:%u",
48  binfo->hal_device->bus_num());
49  break;
50  default:
51  break;
52  }
53  pthread_setname_np(pthread_self(), name);
54 
55  while (!_px4_thread_should_exit) {
56  uint64_t now = AP_HAL::micros64();
57  DeviceBus::callback_info *callback;
58 
59  // find a callback to run
60  for (callback = binfo->callbacks; callback; callback = callback->next) {
61  if (now >= callback->next_usec) {
62  while (now >= callback->next_usec) {
63  callback->next_usec += callback->period_usec;
64  }
65  // call it with semaphore held
67  callback->cb();
68  binfo->semaphore.give();
69  }
70  }
71  }
72 
73  // work out when next loop is needed
74  uint64_t next_needed = 0;
75  now = AP_HAL::micros64();
76 
77  for (callback = binfo->callbacks; callback; callback = callback->next) {
78  if (next_needed == 0 ||
79  callback->next_usec < next_needed) {
80  next_needed = callback->next_usec;
81  if (next_needed < now) {
82  next_needed = now;
83  }
84  }
85  }
86 
87  // delay for at most 50ms, to handle newly added callbacks
88  uint32_t delay = 50000;
89  if (next_needed >= now && next_needed - now < delay) {
90  delay = next_needed - now;
91  }
92  // don't delay for less than 400usec, so one thread doesn't
93  // completely dominate the CPU
94  if (delay < 400) {
95  delay = 400;
96  }
97  hal.scheduler->delay_microseconds(delay);
98  }
99  return nullptr;
100 }
101 
102 AP_HAL::Device::PeriodicHandle DeviceBus::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb, AP_HAL::Device *_hal_device)
103 {
104  if (!thread_started) {
105  thread_started = true;
106 
107  pthread_attr_t thread_attr;
108  struct sched_param param;
109 
110  pthread_attr_init(&thread_attr);
111  pthread_attr_setstacksize(&thread_attr, 1024);
112 
113  param.sched_priority = thread_priority;
114  (void)pthread_attr_setschedparam(&thread_attr, &param);
115  pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
116 
117  hal_device = _hal_device;
118 
119  pthread_create(&thread_ctx, &thread_attr, &DeviceBus::bus_thread, this);
120  }
122  if (callback == nullptr) {
123  return nullptr;
124  }
125  callback->cb = cb;
126  callback->period_usec = period_usec;
127  callback->next_usec = AP_HAL::micros64() + period_usec;
128 
129  // add to linked list of callbacks on thread
130  callback->next = callbacks;
131  callbacks = callback;
132 
133  return callback;
134 }
135 
136 /*
137  * Adjust the timer for the next call: it needs to be called from the bus
138  * thread, otherwise it will race with it
139  */
141 {
142  if (!pthread_equal(pthread_self(), thread_ctx)) {
143  fprintf(stderr, "can't adjust timer from unknown thread context\n");
144  return false;
145  }
146 
147  DeviceBus::callback_info *callback = static_cast<DeviceBus::callback_info *>(h);
148 
149  callback->period_usec = period_usec;
150  callback->next_usec = AP_HAL::micros64() + period_usec;
151 
152  return true;
153 }
154 
155 }
AP_HAL::Device::PeriodicCb cb
Definition: Device.h:39
bool adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
Definition: Device.cpp:140
bool take(uint32_t timeout_ms)
Definition: Semaphores.cpp:17
pthread_t thread_ctx
Definition: Device.h:44
AP_HAL::Device * hal_device
Definition: Device.h:46
bool thread_started
Definition: Device.h:45
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
const char * name
Definition: BusTest.cpp:11
void delay(uint32_t ms)
Definition: system.cpp:91
uint8_t bus_num(void) const
Definition: Device.h:55
uint8_t thread_priority
Definition: Device.h:43
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device)
Definition: Device.cpp:102
struct callback_info * next
Definition: Device.h:38
void * PeriodicHandle
Definition: Device.h:42
enum BusType bus_type(void) const
Definition: Device.h:50
uint64_t micros64()
Definition: system.cpp:162
bool _px4_thread_should_exit
const HAL & get_HAL()
Semaphore semaphore
Definition: Device.h:30
virtual void delay_microseconds(uint16_t us)=0
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
struct PX4::DeviceBus::callback_info * callbacks
static void * bus_thread(void *arg)
Definition: Device.cpp:34
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
static const AP_HAL::HAL & hal
Definition: Device.cpp:29