APM:Libraries
AP_Scheduler.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * main loop scheduler for APM
18  * Author: Andrew Tridgell, January 2013
19  *
20  */
21 #include "AP_Scheduler.h"
22 
23 #include <AP_HAL/AP_HAL.h>
24 #include <AP_Param/AP_Param.h>
25 #include <AP_Vehicle/AP_Vehicle.h>
26 #include <DataFlash/DataFlash.h>
28 
29 #include <stdio.h>
30 
31 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
32 #define SCHEDULER_DEFAULT_LOOP_RATE 400
33 #else
34 #define SCHEDULER_DEFAULT_LOOP_RATE 50
35 #endif
36 
37 #define debug(level, fmt, args...) do { if ((level) <= _debug.get()) { hal.console->printf(fmt, ##args); }} while (0)
38 
39 extern const AP_HAL::HAL& hal;
40 
41 int8_t AP_Scheduler::current_task = -1;
42 
44  // @Param: DEBUG
45  // @DisplayName: Scheduler debug level
46  // @Description: Set to non-zero to enable scheduler debug messages. When set to show "Slips" the scheduler will display a message whenever a scheduled task is delayed due to too much CPU load. When set to ShowOverruns the scheduled will display a message whenever a task takes longer than the limit promised in the task table.
47  // @Values: 0:Disabled,2:ShowSlips,3:ShowOverruns
48  // @User: Advanced
49  AP_GROUPINFO("DEBUG", 0, AP_Scheduler, _debug, 0),
50 
51  // @Param: LOOP_RATE
52  // @DisplayName: Scheduling main loop rate
53  // @Description: This controls the rate of the main control loop in Hz. This should only be changed by developers. This only takes effect on restart. Values over 400 are considered highly experimental.
54  // @Values: 50:50Hz,100:100Hz,200:200Hz,250:250Hz,300:300Hz,400:400Hz
55  // @RebootRequired: True
56  // @User: Advanced
57  AP_GROUPINFO("LOOP_RATE", 1, AP_Scheduler, _loop_rate_hz, SCHEDULER_DEFAULT_LOOP_RATE),
58 
60 };
61 
62 // constructor
63 AP_Scheduler::AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn) :
64  _fastloop_fn(fastloop_fn)
65 {
67 
68  // only allow 50 to 2000 Hz
69  if (_loop_rate_hz < 50) {
70  _loop_rate_hz.set(50);
71  } else if (_loop_rate_hz > 2000) {
72  _loop_rate_hz.set(2000);
73  }
75 }
76 
77 // initialise the scheduler
78 void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit)
79 {
80  _tasks = tasks;
81  _num_tasks = num_tasks;
82  _last_run = new uint16_t[_num_tasks];
83  memset(_last_run, 0, sizeof(_last_run[0]) * _num_tasks);
84  _tick_counter = 0;
85 
86  // setup initial performance counters
88  perf_info.reset();
89 
90  _log_performance_bit = log_performance_bit;
91 }
92 
93 // one tick has passed
95 {
96  _tick_counter++;
97 }
98 
99 /*
100  run one tick
101  this will run as many scheduler tasks as we can in the specified time
102  */
103 void AP_Scheduler::run(uint32_t time_available)
104 {
105  uint32_t run_started_usec = AP_HAL::micros();
106  uint32_t now = run_started_usec;
107 
108  if (_debug > 1 && _perf_counters == nullptr) {
110  if (_perf_counters != nullptr) {
111  for (uint8_t i=0; i<_num_tasks; i++) {
113  }
114  }
115  }
116 
117  for (uint8_t i=0; i<_num_tasks; i++) {
118  uint16_t dt = _tick_counter - _last_run[i];
119  uint16_t interval_ticks = _loop_rate_hz / _tasks[i].rate_hz;
120  if (interval_ticks < 1) {
121  interval_ticks = 1;
122  }
123  if (dt < interval_ticks) {
124  // this task is not yet scheduled to run again
125  continue;
126  }
127  // this task is due to run. Do we have enough time to run it?
129 
130  if (dt >= interval_ticks*2) {
131  // we've slipped a whole run of this task!
132  debug(2, "Scheduler slip task[%u-%s] (%u/%u/%u)\n",
133  (unsigned)i,
134  _tasks[i].name,
135  (unsigned)dt,
136  (unsigned)interval_ticks,
137  (unsigned)_task_time_allowed);
138  }
139 
140  if (_task_time_allowed > time_available) {
141  // not enough time to run this task. Continue loop -
142  // maybe another task will fit into time remaining
143  continue;
144  }
145 
146  // run it
147  _task_time_started = now;
148  current_task = i;
149  if (_debug > 1 && _perf_counters && _perf_counters[i]) {
150  hal.util->perf_begin(_perf_counters[i]);
151  }
152  _tasks[i].function();
153  if (_debug > 1 && _perf_counters && _perf_counters[i]) {
154  hal.util->perf_end(_perf_counters[i]);
155  }
156  current_task = -1;
157 
158  // record the tick counter when we ran. This drives
159  // when we next run the event
160  _last_run[i] = _tick_counter;
161 
162  // work out how long the event actually took
163  now = AP_HAL::micros();
164  uint32_t time_taken = now - _task_time_started;
165 
166  if (time_taken > _task_time_allowed) {
167  // the event overran!
168  debug(3, "Scheduler overrun task[%u-%s] (%u/%u)\n",
169  (unsigned)i,
170  _tasks[i].name,
171  (unsigned)time_taken,
172  (unsigned)_task_time_allowed);
173  }
174  if (time_taken >= time_available) {
175  time_available = 0;
176  break;
177  }
178  time_available -= time_taken;
179  }
180 
181  // update number of spare microseconds
182  _spare_micros += time_available;
183 
184  _spare_ticks++;
185  if (_spare_ticks == 32) {
186  _spare_ticks /= 2;
187  _spare_micros /= 2;
188  }
189 }
190 
191 /*
192  return number of micros until the current task reaches its deadline
193  */
195 {
196  uint32_t dt = AP_HAL::micros() - _task_time_started;
197  if (dt > _task_time_allowed) {
198  return 0;
199  }
200  return _task_time_allowed - dt;
201 }
202 
203 /*
204  calculate load average as a number from 0 to 1
205  */
207 {
208  if (_spare_ticks == 0) {
209  return 0.0f;
210  }
211  const uint32_t loop_us = get_loop_period_us();
212  const uint32_t used_time = loop_us - (_spare_micros/_spare_ticks);
213  return used_time / (float)loop_us;
214 }
215 
217 {
218  // wait for an INS sample
220 
221  const uint32_t sample_time_us = AP_HAL::micros();
222 
223  if (_loop_timer_start_us == 0) {
224  _loop_timer_start_us = sample_time_us;
226  } else {
227  _last_loop_time_s = (sample_time_us - _loop_timer_start_us) * 1.0e-6;
228  }
229 
230  // Execute the fast loop
231  // ---------------------
232  if (_fastloop_fn) {
233  _fastloop_fn();
234  }
235 
236  // tell the scheduler one tick has passed
237  tick();
238 
239  // run all the tasks that are due to run. Note that we only
240  // have to call this once per loop, as the tasks are scheduled
241  // in multiples of the main loop tick. So if they don't run on
242  // the first call to the scheduler they won't run on a later
243  // call until scheduler.tick() is called again
244  const uint32_t loop_us = get_loop_period_us();
245  const uint32_t time_available = (sample_time_us + loop_us) - AP_HAL::micros();
246  run(time_available > loop_us ? 0u : time_available);
247 
248 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
249  // move result of AP_HAL::micros() forward:
251 #endif
252 
253  // check loop time
255 
256  _loop_timer_start_us = sample_time_us;
257 }
258 
260 {
261  if (debug_flags()) {
263  }
264  if (_log_performance_bit != (uint32_t)-1 &&
267  }
269  perf_info.reset();
270 }
271 
272 // Write a performance monitoring packet
274 {
275  struct log_Performance pkt = {
282  load : (uint16_t)(load_average() * 1000)
283  };
284  DataFlash_Class::instance()->WriteCriticalBlock(&pkt, sizeof(pkt));
285 }
virtual uint32_t available_memory(void)
Definition: Util.h:121
scheduler_fastloop_fn_t _fastloop_fn
Definition: AP_Scheduler.h:150
uint8_t debug_flags(void)
Definition: AP_Scheduler.h:102
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name)
Definition: Util.h:102
float load_average()
uint16_t get_loop_rate_hz(void)
Definition: AP_Scheduler.h:110
AP_Int16 _loop_rate_hz
Definition: AP_Scheduler.h:156
void update_logging()
uint32_t get_loop_period_us()
Definition: AP_Scheduler.h:117
float get_loop_period_s()
Definition: AP_Scheduler.h:124
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
void init(const Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit)
static int8_t current_task
Definition: AP_Scheduler.h:143
uint16_t get_num_loops() const
Definition: PerfInfo.cpp:73
AP_HAL::Util * util
Definition: HAL.h:115
static bool _debug
Definition: sumd.cpp:99
AP_HAL::Util::perf_counter_t * _perf_counters
Definition: AP_Scheduler.h:199
uint16_t num_long_running
uint32_t _spare_micros
Definition: AP_Scheduler.h:187
const char * name
Definition: BusTest.cpp:11
uint16_t num_loops
uint32_t mem_avail
uint32_t _task_time_allowed
Definition: AP_Scheduler.h:181
A system for managing and storing variables that are of general interest to the system.
uint8_t _num_tasks
Definition: AP_Scheduler.h:171
void run(uint32_t time_available)
#define debug(level, fmt, args...)
void * perf_counter_t
Definition: Util.h:101
uint16_t * _last_run
Definition: AP_Scheduler.h:178
uint32_t _log_performance_bit
Definition: AP_Scheduler.h:202
void check_loop_time(uint32_t time_in_micros)
Definition: PerfInfo.cpp:32
void tick(void)
uint16_t max_time_micros
Definition: AP_Scheduler.h:71
AP_Int8 _debug
Definition: AP_Scheduler.h:153
void Log_Write_Performance()
void set_loop_rate(uint16_t rate_hz)
Definition: PerfInfo.cpp:126
void update_logging()
Definition: PerfInfo.cpp:114
AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn=nullptr)
virtual void perf_end(perf_counter_t h)
Definition: Util.h:104
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
uint64_t micros64()
Definition: system.cpp:162
void WriteCriticalBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:485
float _last_loop_time_s
Definition: AP_Scheduler.h:196
uint32_t _task_time_started
Definition: AP_Scheduler.h:184
virtual void perf_begin(perf_counter_t h)
Definition: Util.h:103
uint8_t _spare_ticks
Definition: AP_Scheduler.h:190
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
virtual void delay_microseconds(uint16_t us)=0
uint32_t get_max_time() const
Definition: PerfInfo.cpp:79
AP_InertialSensor & ins()
const struct Task * _tasks
Definition: AP_Scheduler.h:168
uint16_t time_available_usec(void)
uint16_t get_num_long_running() const
Definition: PerfInfo.cpp:91
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Scheduler.h:140
#define SCHEDULER_DEFAULT_LOOP_RATE
void reset()
Definition: PerfInfo.cpp:15
uint16_t _tick_counter
Definition: AP_Scheduler.h:175
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
uint32_t micros()
Definition: system.cpp:152
#define AP_GROUPEND
Definition: AP_Param.h:121
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
uint32_t _loop_timer_start_us
Definition: AP_Scheduler.h:193
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
AP::PerfInfo perf_info
Definition: AP_Scheduler.h:146
task_fn_t function
Definition: AP_Scheduler.h:68