123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225 |
- #pragma once
- #include <AP_Param/AP_Param.h>
- #include <AP_HAL/Util.h>
- #include <AP_Math/AP_Math.h>
- #include "PerfInfo.h"
- #define AP_SCHEDULER_NAME_INITIALIZER(_name) .name = #_name,
- #define SCHED_TASK_CLASS(classname, classptr, func, _rate_hz, _max_time_micros) { \
- .function = FUNCTOR_BIND(classptr, &classname::func, void),\
- AP_SCHEDULER_NAME_INITIALIZER(func)\
- .rate_hz = _rate_hz,\
- .max_time_micros = _max_time_micros\
- }
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Vehicle/AP_Vehicle.h>
- class AP_Scheduler
- {
- public:
- FUNCTOR_TYPEDEF(scheduler_fastloop_fn_t, void);
- AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn = nullptr);
-
- AP_Scheduler(const AP_Scheduler &other) = delete;
- AP_Scheduler &operator=(const AP_Scheduler&) = delete;
- static AP_Scheduler *get_singleton();
- static AP_Scheduler *_singleton;
- FUNCTOR_TYPEDEF(task_fn_t, void);
- struct Task {
- task_fn_t function;
- const char *name;
- float rate_hz;
- uint16_t max_time_micros;
- };
-
- void init(const Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit);
-
-
- void loop();
-
- void update_logging();
-
- void Log_Write_Performance();
-
- void tick(void);
-
- uint16_t ticks() const { return _tick_counter; }
-
-
-
- void run(uint32_t time_available);
-
- uint16_t time_available_usec(void);
-
- uint8_t debug_flags(void) { return _debug; }
-
-
-
- float load_average();
-
- uint16_t get_loop_rate_hz(void) {
- if (_active_loop_rate_hz == 0) {
- _active_loop_rate_hz = _loop_rate_hz;
- }
- return _active_loop_rate_hz;
- }
-
- uint32_t get_loop_period_us() {
- if (_loop_period_us == 0) {
- _loop_period_us = 1000000UL / _loop_rate_hz;
- }
- return _loop_period_us;
- }
-
- float get_loop_period_s() {
- if (is_zero(_loop_period_s)) {
- _loop_period_s = 1.0f / _loop_rate_hz;
- }
- return _loop_period_s;
- }
- float get_filtered_loop_time(void) const {
- return perf_info.get_filtered_time();
- }
-
- float get_last_loop_time_s(void) const {
- return _last_loop_time_s;
- }
-
- uint32_t get_extra_loop_us(void) const {
- return extra_loop_us;
- }
- static const struct AP_Param::GroupInfo var_info[];
-
- AP::PerfInfo perf_info;
- private:
-
- scheduler_fastloop_fn_t _fastloop_fn;
-
- AP_Int8 _debug;
-
- AP_Int16 _loop_rate_hz;
-
- AP_Int16 _active_loop_rate_hz;
-
-
- uint16_t _loop_period_us;
-
- float _loop_period_s;
-
-
- const struct Task *_tasks;
-
- uint8_t _num_tasks;
-
-
- uint16_t _tick_counter;
-
- uint16_t *_last_run;
-
- uint32_t _task_time_allowed;
-
- uint32_t _task_time_started;
-
- uint32_t _spare_micros;
-
- uint8_t _spare_ticks;
-
- uint32_t _loop_timer_start_us;
-
- float _last_loop_time_s;
-
-
- AP_HAL::Util::perf_counter_t *_perf_counters;
-
- uint32_t _log_performance_bit;
-
-
- const uint8_t max_task_slowdown = 4;
-
-
- uint32_t task_not_achieved;
- uint32_t task_all_achieved;
-
-
-
- uint32_t extra_loop_us;
- };
- namespace AP {
- AP_Scheduler &scheduler();
- };
|