APM:Libraries
Semaphores.h
Go to the documentation of this file.
1 
2 #pragma once
3 
4 #include <AP_HAL/AP_HAL.h>
6 #include <exti.h>
7 #include "Config.h"
8 
9 #ifdef SEM_DEBUG
10 #define SEM_LOG_SIZE 500
11 enum Sem_OP {
12  Sem_Give,
13  Sem_Take,
14  Sem_Take_Nonblocking
15 };
16 
17 class F4Light::Semaphore;
18 
19 typedef struct SEM_LOG {
20  uint32_t time;
21  F4Light::Semaphore *sem;
22  void * task;
23  enum Sem_OP op;
24  bool result;
25 } Sem_Log;
26 
27 Sem_Log sem_log[SEM_LOG_SIZE];
28 
29 #endif
30 
31 
33 public: // interface
34  Semaphore();
35  bool give();
36  bool take(uint32_t timeout_ms);
37  bool take_nonblocking();
38 
39 //[ functions that called by scheduler only in SVC level so need not to disable interrupts
40  bool svc_give();
41  bool svc_take(uint32_t timeout_ms);
42  bool svc_take_nonblocking();
43  inline void *get_owner() { return _task; } // task that owns this semaphore
44  inline bool is_taken() { return _taken; }
45  inline bool is_waiting() { return _is_waiting; } // does anyone want this semaphore when it was busy?
46 //]
47 
48 #ifdef SEM_DEBUG
49  static Sem_Log sem_log[SEM_LOG_SIZE];
50  static uint16_t sem_log_ptr;
51 #endif
52 
53 protected:
54  bool _take_from_mainloop(uint32_t timeout_ms);
55  bool _take_nonblocking();
56  bool _give();
57 
58  volatile bool _taken;
59  void * _task; // owner
61 };
62 
63 
const char * result
Definition: Printf.cpp:16
volatile bool _taken
Definition: Semaphores.h:58
void * get_owner()
Definition: Semaphores.h:43