APM:Libraries
Semaphores.cpp
Go to the documentation of this file.
1 
3 /*
4 
5 (c) 2017 night_ghost@ykoctpa.ru
6 
7 */
8 
9 #pragma GCC optimize ("O2")
10 
12 #include "Semaphores.h"
13 #include "Scheduler.h"
14 
15 using namespace F4Light;
16 
17 extern const AP_HAL::HAL& hal;
18 
19 #ifdef SEM_PROF
20 uint64_t Semaphore::sem_time=0;
21 #endif
22 
23 // Constructor
25  : _taken(false)
26  , _task(NULL)
27  , _is_waiting(false)
28 {}
29 
30 
32  if(Scheduler::in_interrupt()) { // SVC from interrupt will cause HardFault, but we need to give
33  bool v=_is_waiting; // bus semaphores from IO_Complete ISR.
34  bool ret=svc_give(); // This is atomic and don't breaks anything
35  if(v) Scheduler::context_switch_isr(); // if anyone waits for this semaphore then reschedule tasks after interrupt
36  return ret;
37  }
38  return _give();
39 }
40 
42  return _take_nonblocking();
43 }
44 
45 bool Semaphore::take(uint32_t timeout_ms) {
46  uint32_t now=Scheduler::_micros();
47  uint32_t dt = timeout_ms*1000;
48  bool ret;
49  do { // task switching can be asyncronous but we can't return to caller before take semaphore
50 
51  if(Scheduler::in_interrupt()) { // SVC from interrupt will cause HardFault
52  ret = svc_take_nonblocking(); // but this can be called from failsafe_check which executed in ISR context
53  } else {
54  ret = _take_from_mainloop(timeout_ms);
55  }
56  if(ret) break;
57  }while(Scheduler::_micros()-now < dt || timeout_ms==HAL_SEMAPHORE_BLOCK_FOREVER);
58 
59  return ret;
60 }
61 
62 
63 // realization
65  asm volatile("svc 1 \r\n"
66  "bx lr \r\n");
67 }
68 
69 bool NAKED Semaphore::_take_from_mainloop(uint32_t timeout_ms) {
70  asm volatile("svc 2 \r\n"
71  "bx lr \r\n");
72 
73 }
74 
76  asm volatile("svc 3 \r\n"
77  "bx lr \r\n");
78 }
79 
80 
81 #ifdef SEM_DEBUG
82 void Semaphore::save_log(enum Sem_OP op, bool result){
83  Sem_Log *lp = sem_log[sem_log_ptr++];
84  if(sem_log_ptr >= SEM_LOG_SIZE) sem_log_ptr=0;
85 
86  lp.time=Scheduler::_micros();
87  lp.sem = this;
89  lp.op = op;
90  lp.result=result;
91 
92 #endif
93 
94 // this functions called only at SVC level so serialized by hardware and don't needs to disable interrupts
95 
97  _is_waiting=false;
98  if (_taken) {
99  _taken = false;
100  _task = NULL;
101 #ifdef SEM_DEBUG
102  save_log(Sem_Give, true);
103 #endif
104  return true;
105  }
106 #ifdef SEM_DEBUG
107  save_log(Sem_Give, false);
108 #endif
109  return false;
110 }
111 
113  void *me = Scheduler::get_current_task_isr();
114  if (!_taken) {
115  _taken = true;
116  _task = me; // remember task which owns semaphore
117 #ifdef SEM_DEBUG
118  save_log(Sem_Take_Nonblocking, true);
119 #endif
120  return true;
121  }
122 
123  if(_task == me){ // the current task already owns this semaphore
124 #ifdef SEM_DEBUG
125  save_log(Sem_Take_Nonblocking, true);
126 #endif
127  return true;
128  }
129  _is_waiting=true;
130 #ifdef SEM_DEBUG
131  save_log(Sem_Take_Nonblocking, false);
132 #endif
133  return false;
134 }
135 
136 bool Semaphore::svc_take(uint32_t timeout_ms) {
137  void *me = Scheduler::get_current_task_isr();
138  if (!_taken) {
139  _taken = true;
140  _task = me; // remember task which owns semaphore
141 #ifdef SEM_DEBUG
142  save_log(Sem_Take, true);
143 #endif
144  return true;
145  }
146  if(_task == me){ // the current task already owns this semaphore
147 #ifdef SEM_DEBUG
148  save_log(Sem_Take, true);
149 #endif
150  return true;
151  }
152  _is_waiting=true;
153 #ifdef SEM_DEBUG
154  save_log(Sem_Take, false);
155 #endif
156  return false;
157 }
158 
bool svc_take_nonblocking()
Definition: Semaphores.cpp:112
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
static void context_switch_isr()
Definition: Scheduler.h:312
#define NAKED
Definition: hal_types.h:46
bool _take_from_mainloop(uint32_t timeout_ms)
Definition: Semaphores.cpp:69
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
static bool in_interrupt()
Definition: Scheduler.h:240
bool svc_take(uint32_t timeout_ms)
Definition: Semaphores.cpp:136
const char * result
Definition: Printf.cpp:16
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
volatile bool _taken
Definition: Semaphores.h:58
float v
Definition: Printf.cpp:15
#define NULL
Definition: hal_types.h:59
static uint32_t _micros()
Definition: Scheduler.h:232
static void * get_current_task_isr()
Definition: Scheduler.h:303
bool take(uint32_t timeout_ms)
Definition: Semaphores.cpp:45
bool _take_nonblocking()
Definition: Semaphores.cpp:75