APM:Libraries
AP_Scheduler.h
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 #pragma once
22 
23 #include <AP_Param/AP_Param.h>
24 #include <AP_HAL/Util.h>
25 #include <AP_Math/AP_Math.h>
26 #include "PerfInfo.h" // loop perf monitoring
27 
28 #define AP_SCHEDULER_NAME_INITIALIZER(_name) .name = #_name,
29 
30 /*
31  useful macro for creating scheduler task table
32  */
33 #define SCHED_TASK_CLASS(classname, classptr, func, _rate_hz, _max_time_micros) { \
34  .function = FUNCTOR_BIND(classptr, &classname::func, void),\
35  AP_SCHEDULER_NAME_INITIALIZER(func)\
36  .rate_hz = _rate_hz,\
37  .max_time_micros = _max_time_micros\
38 }
39 
40 /*
41  A task scheduler for APM main loops
42 
43  Sketches should call scheduler.init() on startup, then call
44  scheduler.tick() at regular intervals (typically every 10ms).
45 
46  To run tasks use scheduler.run(), passing the amount of time that
47  the scheduler is allowed to use before it must return
48  */
49 
50 #include <AP_HAL/AP_HAL.h>
51 #include <AP_Vehicle/AP_Vehicle.h>
52 
54 {
55 public:
56 
57  FUNCTOR_TYPEDEF(scheduler_fastloop_fn_t, void);
58 
59  AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn = nullptr);
60 
61  /* Do not allow copies */
62  AP_Scheduler(const AP_Scheduler &other) = delete;
63  AP_Scheduler &operator=(const AP_Scheduler&) = delete;
64 
65  FUNCTOR_TYPEDEF(task_fn_t, void);
66 
67  struct Task {
68  task_fn_t function;
69  const char *name;
70  float rate_hz;
71  uint16_t max_time_micros;
72  };
73 
74  // initialise scheduler
75  void init(const Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit);
76 
77  // called by vehicle's main loop - which should be the only thing
78  // that function does
79  void loop();
80 
81  // call to update any logging the scheduler might do; call at 1Hz
82  void update_logging();
83 
84  // write out PERF message to dataflash
85  void Log_Write_Performance();
86 
87  // call when one tick has passed
88  void tick(void);
89 
90  // return current tick counter
91  uint16_t ticks() const { return _tick_counter; }
92 
93  // run the tasks. Call this once per 'tick'.
94  // time_available is the amount of time available to run
95  // tasks in microseconds
96  void run(uint32_t time_available);
97 
98  // return the number of microseconds available for the current task
99  uint16_t time_available_usec(void);
100 
101  // return debug parameter
102  uint8_t debug_flags(void) { return _debug; }
103 
104  // return load average, as a number between 0 and 1. 1 means
105  // 100% load. Calculated from how much spare time we have at the
106  // end of a run()
107  float load_average();
108 
109  // get the active main loop rate
110  uint16_t get_loop_rate_hz(void) {
111  if (_active_loop_rate_hz == 0) {
113  }
114  return _active_loop_rate_hz;
115  }
116  // get the time-allowed-per-loop in microseconds
117  uint32_t get_loop_period_us() {
118  if (_loop_period_us == 0) {
119  _loop_period_us = 1000000UL / _loop_rate_hz;
120  }
121  return _loop_period_us;
122  }
123  // get the time-allowed-per-loop in seconds
125  if (is_zero(_loop_period_s)) {
127  }
128  return _loop_period_s;
129  }
130 
131  float get_filtered_loop_time(void) const {
132  return perf_info.get_filtered_time();
133  }
134 
135  // get the time in seconds that the last loop took
136  float get_last_loop_time_s(void) const {
137  return _last_loop_time_s;
138  }
139 
140  static const struct AP_Param::GroupInfo var_info[];
141 
142  // current running task, or -1 if none. Used to debug stuck tasks
143  static int8_t current_task;
144 
145  // loop performance monitoring:
147 
148 private:
149  // function that is called before anything in the scheduler table:
150  scheduler_fastloop_fn_t _fastloop_fn;
151 
152  // used to enable scheduler debugging
153  AP_Int8 _debug;
154 
155  // overall scheduling rate in Hz
156  AP_Int16 _loop_rate_hz;
157 
158  // loop rate in Hz as set at startup
160 
161  // calculated loop period in usec
162  uint16_t _loop_period_us;
163 
164  // calculated loop period in seconds
166 
167  // progmem list of tasks to run
168  const struct Task *_tasks;
169 
170  // number of tasks in _tasks list
171  uint8_t _num_tasks;
172 
173  // number of 'ticks' that have passed (number of times that
174  // tick() has been called
175  uint16_t _tick_counter;
176 
177  // tick counter at the time we last ran each task
178  uint16_t *_last_run;
179 
180  // number of microseconds allowed for the current task
182 
183  // the time in microseconds when the task started
185 
186  // number of spare microseconds accumulated
187  uint32_t _spare_micros;
188 
189  // number of ticks that _spare_micros is counted over
190  uint8_t _spare_ticks;
191 
192  // start of loop timing
194 
195  // time of last loop in seconds
197 
198  // performance counters
200 
201  // bitmask bit which indicates if we should log PERF message to dataflash
203 };
uint16_t ticks() const
Definition: AP_Scheduler.h:91
scheduler_fastloop_fn_t _fastloop_fn
Definition: AP_Scheduler.h:150
uint8_t debug_flags(void)
Definition: AP_Scheduler.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
static int8_t current_task
Definition: AP_Scheduler.h:143
void init(const Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit)
float get_filtered_time() const
Definition: PerfInfo.cpp:109
float get_last_loop_time_s(void) const
Definition: AP_Scheduler.h:136
AP_Scheduler & operator=(const AP_Scheduler &)=delete
AP_HAL::Util::perf_counter_t * _perf_counters
Definition: AP_Scheduler.h:199
uint32_t _spare_micros
Definition: AP_Scheduler.h:187
uint32_t _task_time_allowed
Definition: AP_Scheduler.h:181
float _loop_period_s
Definition: AP_Scheduler.h:165
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)
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 tick(void)
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
uint16_t max_time_micros
Definition: AP_Scheduler.h:71
const char * name
Definition: AP_Scheduler.h:69
AP_Int8 _debug
Definition: AP_Scheduler.h:153
void Log_Write_Performance()
AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn=nullptr)
float _last_loop_time_s
Definition: AP_Scheduler.h:196
uint32_t _task_time_started
Definition: AP_Scheduler.h:184
uint16_t _loop_period_us
Definition: AP_Scheduler.h:162
uint8_t _spare_ticks
Definition: AP_Scheduler.h:190
float get_filtered_loop_time(void) const
Definition: AP_Scheduler.h:131
const struct Task * _tasks
Definition: AP_Scheduler.h:168
uint16_t time_available_usec(void)
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Scheduler.h:140
AP_Int16 _active_loop_rate_hz
Definition: AP_Scheduler.h:159
uint16_t _tick_counter
Definition: AP_Scheduler.h:175
uint32_t _loop_timer_start_us
Definition: AP_Scheduler.h:193
FUNCTOR_TYPEDEF(scheduler_fastloop_fn_t, void)
AP::PerfInfo perf_info
Definition: AP_Scheduler.h:146