31 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduSub) 32 #define SCHEDULER_DEFAULT_LOOP_RATE 400 34 #define SCHEDULER_DEFAULT_LOOP_RATE 50 37 #define debug(level, fmt, args...) do { if ((level) <= _debug.get()) { hal.console->printf(fmt, ##args); }} while (0) 64 _fastloop_fn(fastloop_fn)
106 uint32_t now = run_started_usec;
120 if (interval_ticks < 1) {
123 if (dt < interval_ticks) {
130 if (dt >= interval_ticks*2) {
132 debug(2,
"Scheduler slip task[%u-%s] (%u/%u/%u)\n",
136 (
unsigned)interval_ticks,
168 debug(3,
"Scheduler overrun task[%u-%s] (%u/%u)\n",
171 (
unsigned)time_taken,
174 if (time_taken >= time_available) {
178 time_available -= time_taken;
213 return used_time / (float)loop_us;
245 const uint32_t time_available = (sample_time_us + loop_us) -
AP_HAL::micros();
246 run(time_available > loop_us ? 0u : time_available);
248 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
virtual uint32_t available_memory(void)
scheduler_fastloop_fn_t _fastloop_fn
uint8_t debug_flags(void)
virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name)
uint16_t get_loop_rate_hz(void)
uint32_t get_loop_period_us()
float get_loop_period_s()
#define AP_GROUPINFO(name, idx, clazz, element, def)
void init(const Task *tasks, uint8_t num_tasks, uint32_t log_performance_bit)
static int8_t current_task
uint16_t get_num_loops() const
AP_HAL::Util::perf_counter_t * _perf_counters
uint32_t _task_time_allowed
A system for managing and storing variables that are of general interest to the system.
void run(uint32_t time_available)
#define debug(level, fmt, args...)
uint32_t _log_performance_bit
void check_loop_time(uint32_t time_in_micros)
void Log_Write_Performance()
void set_loop_rate(uint16_t rate_hz)
AP_Scheduler(scheduler_fastloop_fn_t fastloop_fn=nullptr)
virtual void perf_end(perf_counter_t h)
static DataFlash_Class * instance(void)
void WriteCriticalBlock(const void *pBuffer, uint16_t size)
uint32_t _task_time_started
virtual void perf_begin(perf_counter_t h)
void wait_for_sample(void)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
virtual void delay_microseconds(uint16_t us)=0
uint32_t get_max_time() const
AP_InertialSensor & ins()
const struct Task * _tasks
uint16_t time_available_usec(void)
uint16_t get_num_long_running() const
static const struct AP_Param::GroupInfo var_info[]
#define SCHEDULER_DEFAULT_LOOP_RATE
#define LOG_PACKET_HEADER_INIT(id)
AP_HAL::Scheduler * scheduler
uint32_t _loop_timer_start_us
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)