uc_stm32_thread.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Pavel Kirienko <pavel.kirienko@gmail.com>
3  */
4 
6 #include <uavcan_stm32/clock.hpp>
7 #include <uavcan_stm32/can.hpp>
8 #include "internal.hpp"
9 
10 
11 namespace uavcan_stm32
12 {
13 
14 #if UAVCAN_STM32_CHIBIOS
15 /*
16  * BusEvent
17  */
18 bool BusEvent::wait(uavcan::MonotonicDuration duration)
19 {
20  // set maximum time to allow for 16 bit timers running at 1MHz
21  static const uavcan::int64_t MaxDelayUSec = 0x000FFFF;
22 
23  const uavcan::int64_t usec = duration.toUSec();
24  msg_t ret = msg_t();
25 
26  if (usec <= 0)
27  {
28 # if (CH_KERNEL_MAJOR == 2)
29  ret = sem_.waitTimeout(TIME_IMMEDIATE);
30 # else // ChibiOS 3+
31  ret = sem_.wait(TIME_IMMEDIATE);
32 # endif
33  }
34  else
35  {
36 # if (CH_KERNEL_MAJOR == 2)
37  ret = sem_.waitTimeout((usec > MaxDelayUSec) ? US2ST(MaxDelayUSec) : US2ST(usec));
38 # elif defined(MS2ST) // ChibiOS 3+
39  ret = sem_.wait((usec > MaxDelayUSec) ? US2ST(MaxDelayUSec) : US2ST(usec));
40 # else // ChibiOS 17+
41  ret = sem_.wait(::systime_t((usec > MaxDelayUSec) ? TIME_US2I(MaxDelayUSec) : TIME_US2I(usec)));
42 # endif
43  }
44 # if (CH_KERNEL_MAJOR == 2)
45  return ret == RDY_OK;
46 # else // ChibiOS 3+
47  return ret == MSG_OK;
48 # endif
49 }
50 
51 void BusEvent::signal()
52 {
53  sem_.signal();
54 }
55 
56 void BusEvent::signalFromInterrupt()
57 {
58 # if (CH_KERNEL_MAJOR == 2)
59  chSysLockFromIsr();
60  sem_.signalI();
61  chSysUnlockFromIsr();
62 # else // ChibiOS 3+
63  chSysLockFromISR();
64  sem_.signalI();
65  chSysUnlockFromISR();
66 # endif
67 }
68 
69 /*
70  * Mutex
71  */
72 void Mutex::lock()
73 {
74  mtx_.lock();
75 }
76 
77 void Mutex::unlock()
78 {
79 # if (CH_KERNEL_MAJOR == 2)
80  chibios_rt::BaseThread::unlockMutex();
81 # else // ChibiOS 3+
82  mtx_.unlock();
83 # endif
84 }
85 
86 
87 #elif UAVCAN_STM32_FREERTOS
88 
89 bool BusEvent::wait(uavcan::MonotonicDuration duration)
90 {
91  static const uavcan::int64_t MaxDelayMSec = 0x000FFFFF;
92 
93  const uavcan::int64_t msec = duration.toMSec();
94 
95  BaseType_t ret;
96 
97  if (msec <= 0)
98  {
99  ret = xSemaphoreTake( sem_, ( TickType_t ) 0 );
100  }
101  else
102  {
103  ret = xSemaphoreTake( sem_, (msec > MaxDelayMSec) ? (MaxDelayMSec/portTICK_RATE_MS) : (msec/portTICK_RATE_MS));
104  }
105  return ret == pdTRUE;
106 }
107 
108 void BusEvent::signal()
109 {
110  xSemaphoreGive( sem_ );
111 }
112 
113 void BusEvent::signalFromInterrupt()
114 {
115  higher_priority_task_woken = pdFALSE;
116 
117  xSemaphoreGiveFromISR( sem_, &higher_priority_task_woken );
118 }
119 
120 void BusEvent::yieldFromISR()
121 {
122  portYIELD_FROM_ISR( higher_priority_task_woken );
123 }
124 
125 /*
126  * Mutex
127  */
128 void Mutex::lock()
129 {
130  xSemaphoreTake( mtx_, portMAX_DELAY );
131 }
132 
133 void Mutex::unlock()
134 {
135  xSemaphoreGive( mtx_ );
136 }
137 
138 
139 #elif UAVCAN_STM32_NUTTX
140 
141 const unsigned BusEvent::MaxPollWaiters;
142 const char* const BusEvent::DevName = "/dev/uavcan/busevent";
143 
144 int BusEvent::openTrampoline(::file* filp)
145 {
146  return static_cast<BusEvent*>(filp->f_inode->i_private)->open(filp);
147 }
148 
149 int BusEvent::closeTrampoline(::file* filp)
150 {
151  return static_cast<BusEvent*>(filp->f_inode->i_private)->close(filp);
152 }
153 
154 int BusEvent::pollTrampoline(::file* filp, ::pollfd* fds, bool setup)
155 {
156  return static_cast<BusEvent*>(filp->f_inode->i_private)->poll(filp, fds, setup);
157 }
158 
159 int BusEvent::open(::file* filp)
160 {
161  (void)filp;
162  return 0;
163 }
164 
165 int BusEvent::close(::file* filp)
166 {
167  (void)filp;
168  return 0;
169 }
170 
171 int BusEvent::poll(::file* filp, ::pollfd* fds, bool setup)
172 {
173  CriticalSectionLocker locker;
174  int ret = -1;
175 
176  if (setup)
177  {
178  ret = addPollWaiter(fds);
179  if (ret == 0)
180  {
181  /*
182  * Two events can be reported via POLLIN:
183  * - The RX queue is not empty. This event is level-triggered.
184  * - Transmission complete. This event is edge-triggered.
185  * FIXME Since TX event is edge-triggered, it can be lost between poll() calls.
186  */
187  fds->revents |= fds->events & (can_driver_.hasReadableInterfaces() ? POLLIN : 0);
188  if (fds->revents != 0)
189  {
190  (void)sem_post(fds->sem);
191  }
192  }
193  }
194  else
195  {
196  ret = removePollWaiter(fds);
197  }
198 
199  return ret;
200 }
201 
202 int BusEvent::addPollWaiter(::pollfd* fds)
203 {
204  for (unsigned i = 0; i < MaxPollWaiters; i++)
205  {
206  if (pollset_[i] == UAVCAN_NULLPTR)
207  {
208  pollset_[i] = fds;
209  return 0;
210  }
211  }
212  return -ENOMEM;
213 }
214 
215 int BusEvent::removePollWaiter(::pollfd* fds)
216 {
217  for (unsigned i = 0; i < MaxPollWaiters; i++)
218  {
219  if (fds == pollset_[i])
220  {
221  pollset_[i] = UAVCAN_NULLPTR;
222  return 0;
223  }
224  }
225  return -EINVAL;
226 }
227 
228 BusEvent::BusEvent(CanDriver& can_driver)
229  : can_driver_(can_driver)
230  , signal_(false)
231 {
232  std::memset(&file_ops_, 0, sizeof(file_ops_));
233  std::memset(pollset_, 0, sizeof(pollset_));
234  file_ops_.open = &BusEvent::openTrampoline;
235  file_ops_.close = &BusEvent::closeTrampoline;
236  file_ops_.poll = &BusEvent::pollTrampoline;
237  // TODO: move to init(), add proper error handling
238  if (register_driver(DevName, &file_ops_, 0666, static_cast<void*>(this)) != 0)
239  {
240  std::abort();
241  }
242 }
243 
244 BusEvent::~BusEvent()
245 {
246  (void)unregister_driver(DevName);
247 }
248 
249 bool BusEvent::wait(uavcan::MonotonicDuration duration)
250 {
251  // TODO blocking wait
252  const uavcan::MonotonicTime deadline = clock::getMonotonic() + duration;
253  while (clock::getMonotonic() < deadline)
254  {
255  {
256  CriticalSectionLocker locker;
257  if (signal_)
258  {
259  signal_ = false;
260  return true;
261  }
262  }
263  ::usleep(1000);
264  }
265  return false;
266 }
267 
268 void BusEvent::signalFromInterrupt()
269 {
270  signal_ = true; // HACK
271  for (unsigned i = 0; i < MaxPollWaiters; i++)
272  {
273  ::pollfd* const fd = pollset_[i];
274  if (fd != UAVCAN_NULLPTR)
275  {
276  fd->revents |= fd->events & POLLIN;
277  if ((fd->revents != 0) && (fd->sem->semcount <= 0))
278  {
279  (void)sem_post(fd->sem);
280  }
281  }
282  }
283 }
284 
285 #endif
286 
287 }
setup
UAVCAN_NULLPTR
#define UAVCAN_NULLPTR
Definition: libuavcan/libuavcan/include/uavcan/build_config.hpp:51
uavcan::DurationBase::toMSec
int64_t toMSec() const
Definition: time.hpp:44
thread.hpp
can.hpp
uavcan_stm32
Definition: bxcan.hpp:22
internal.hpp
uavcan::int64_t
std::int64_t int64_t
Definition: std.hpp:32
uavcan::MonotonicDuration
Definition: time.hpp:182
pyuavcan_v0.file
file
Definition: pyuavcan/pyuavcan_v0/__init__.py:42
uavcan_kinetis::clock::getMonotonic
uavcan::MonotonicTime getMonotonic()
Definition: clock.cpp:83
clock.hpp
uavcan::MonotonicTime
Definition: time.hpp:184
uavcan::DurationBase::toUSec
int64_t toUSec() const
Definition: time.hpp:43


uavcan_communicator
Author(s):
autogenerated on Fri Dec 13 2024 03:10:03