2013-08-29 02:34:34 -03:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
2013-01-11 20:59:20 -04:00
/*
* main loop scheduler for APM
* Author : Andrew Tridgell , January 2013
*
*/
2015-10-26 09:01:52 -03:00
# include "AP_Scheduler.h"
2013-01-11 20:59:20 -04:00
2015-08-11 03:28:45 -03:00
# include <AP_HAL/AP_HAL.h>
# include <AP_Param/AP_Param.h>
2015-11-30 15:59:07 -04:00
# include <AP_Vehicle/AP_Vehicle.h>
2019-01-18 00:23:42 -04:00
# include <AP_Logger/AP_Logger.h>
2017-11-13 03:11:27 -04:00
# include <AP_InertialSensor/AP_InertialSensor.h>
2018-08-07 06:59:37 -03:00
# include <AP_InternalError/AP_InternalError.h>
2019-09-17 05:13:28 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
# include <SITL/SITL.h>
# endif
2016-04-21 01:50:15 -03:00
# include <stdio.h>
2015-11-30 15:59:07 -04:00
2016-02-22 16:48:31 -04:00
# if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
2015-11-30 15:59:07 -04:00
# define SCHEDULER_DEFAULT_LOOP_RATE 400
# else
# define SCHEDULER_DEFAULT_LOOP_RATE 50
2016-06-04 22:20:09 -03:00
# endif
2018-01-18 21:27:43 -04:00
# define debug(level, fmt, args...) do { if ((level) <= _debug.get()) { hal.console->printf(fmt, ##args); }} while (0)
2013-01-11 20:59:20 -04:00
extern const AP_HAL : : HAL & hal ;
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo AP_Scheduler : : var_info [ ] = {
2013-01-11 20:59:20 -04:00
// @Param: DEBUG
// @DisplayName: Scheduler debug level
2013-08-30 02:33:30 -03:00
// @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.
2013-10-13 07:39:33 -03:00
// @Values: 0:Disabled,2:ShowSlips,3:ShowOverruns
2013-01-11 20:59:20 -04:00
// @User: Advanced
AP_GROUPINFO ( " DEBUG " , 0 , AP_Scheduler , _debug , 0 ) ,
2015-11-30 15:59:07 -04:00
// @Param: LOOP_RATE
// @DisplayName: Scheduling main loop rate
2018-01-15 22:22:32 -04:00
// @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.
2016-01-03 17:37:31 -04:00
// @Values: 50:50Hz,100:100Hz,200:200Hz,250:250Hz,300:300Hz,400:400Hz
2015-11-30 15:59:07 -04:00
// @RebootRequired: True
// @User: Advanced
AP_GROUPINFO ( " LOOP_RATE " , 1 , AP_Scheduler , _loop_rate_hz , SCHEDULER_DEFAULT_LOOP_RATE ) ,
2013-01-11 20:59:20 -04:00
AP_GROUPEND
} ;
2015-11-30 15:59:07 -04:00
// constructor
2017-11-13 03:11:27 -04:00
AP_Scheduler : : AP_Scheduler ( scheduler_fastloop_fn_t fastloop_fn ) :
_fastloop_fn ( fastloop_fn )
2015-11-30 15:59:07 -04:00
{
2019-02-10 01:03:20 -04:00
if ( _singleton ) {
2018-05-03 21:44:50 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
AP_HAL : : panic ( " Too many schedulers " ) ;
# endif
return ;
}
2019-02-10 01:03:20 -04:00
_singleton = this ;
2018-05-03 21:44:50 -03:00
2015-11-30 15:59:07 -04:00
AP_Param : : setup_object_defaults ( this , var_info ) ;
2018-01-15 22:22:32 -04:00
// only allow 50 to 2000 Hz
2016-01-03 17:37:31 -04:00
if ( _loop_rate_hz < 50 ) {
2015-11-30 15:59:07 -04:00
_loop_rate_hz . set ( 50 ) ;
2018-01-15 22:22:32 -04:00
} else if ( _loop_rate_hz > 2000 ) {
_loop_rate_hz . set ( 2000 ) ;
2015-11-30 15:59:07 -04:00
}
2018-02-13 01:48:10 -04:00
_last_loop_time_s = 1.0 / _loop_rate_hz ;
2015-11-30 15:59:07 -04:00
}
2018-05-03 21:44:50 -03:00
/*
* Get the AP_Scheduler singleton
*/
2019-02-10 01:03:20 -04:00
AP_Scheduler * AP_Scheduler : : _singleton ;
AP_Scheduler * AP_Scheduler : : get_singleton ( )
2018-05-03 21:44:50 -03:00
{
2019-02-10 01:03:20 -04:00
return _singleton ;
2018-05-03 21:44:50 -03:00
}
2013-01-11 20:59:20 -04:00
// initialise the scheduler
2018-02-09 18:38:17 -04:00
void AP_Scheduler : : init ( const AP_Scheduler : : Task * tasks , uint8_t num_tasks , uint32_t log_performance_bit )
2013-01-11 20:59:20 -04:00
{
_tasks = tasks ;
_num_tasks = num_tasks ;
_last_run = new uint16_t [ _num_tasks ] ;
2013-04-17 10:01:13 -03:00
memset ( _last_run , 0 , sizeof ( _last_run [ 0 ] ) * _num_tasks ) ;
_tick_counter = 0 ;
2017-11-13 03:11:27 -04:00
// setup initial performance counters
perf_info . set_loop_rate ( get_loop_rate_hz ( ) ) ;
perf_info . reset ( ) ;
2018-02-09 18:38:17 -04:00
_log_performance_bit = log_performance_bit ;
2013-01-11 20:59:20 -04:00
}
// one tick has passed
void AP_Scheduler : : tick ( void )
{
_tick_counter + + ;
}
/*
run one tick
this will run as many scheduler tasks as we can in the specified time
*/
2016-07-25 19:27:24 -03:00
void AP_Scheduler : : run ( uint32_t time_available )
2013-01-11 20:59:20 -04:00
{
2015-11-19 23:14:32 -04:00
uint32_t run_started_usec = AP_HAL : : micros ( ) ;
2013-10-10 00:13:44 -03:00
uint32_t now = run_started_usec ;
2017-04-29 03:44:18 -03:00
if ( _debug > 1 & & _perf_counters = = nullptr ) {
2016-04-21 01:50:15 -03:00
_perf_counters = new AP_HAL : : Util : : perf_counter_t [ _num_tasks ] ;
if ( _perf_counters ! = nullptr ) {
for ( uint8_t i = 0 ; i < _num_tasks ; i + + ) {
_perf_counters [ i ] = hal . util - > perf_alloc ( AP_HAL : : Util : : PC_ELAPSED , _tasks [ i ] . name ) ;
}
}
}
2013-01-11 20:59:20 -04:00
for ( uint8_t i = 0 ; i < _num_tasks ; i + + ) {
2019-09-17 05:13:28 -03:00
uint32_t dt = _tick_counter - _last_run [ i ] ;
uint32_t interval_ticks = _loop_rate_hz / _tasks [ i ] . rate_hz ;
2015-11-30 15:59:07 -04:00
if ( interval_ticks < 1 ) {
interval_ticks = 1 ;
}
2018-02-13 02:39:19 -04:00
if ( dt < interval_ticks ) {
// this task is not yet scheduled to run again
continue ;
}
// this task is due to run. Do we have enough time to run it?
_task_time_allowed = _tasks [ i ] . max_time_micros ;
if ( dt > = interval_ticks * 2 ) {
// we've slipped a whole run of this task!
debug ( 2 , " Scheduler slip task[%u-%s] (%u/%u/%u) \n " ,
( unsigned ) i ,
_tasks [ i ] . name ,
( unsigned ) dt ,
( unsigned ) interval_ticks ,
( unsigned ) _task_time_allowed ) ;
}
2019-09-17 05:13:28 -03:00
if ( dt > = interval_ticks * max_task_slowdown ) {
// we are going beyond the maximum slowdown factor for a
// task. This will trigger increasing the time budget
task_not_achieved + + ;
}
2018-02-13 02:40:38 -04:00
if ( _task_time_allowed > time_available ) {
// not enough time to run this task. Continue loop -
// maybe another task will fit into time remaining
continue ;
}
// run it
_task_time_started = now ;
2019-05-09 07:47:10 -03:00
hal . util - > persistent_data . scheduler_task = i ;
2018-02-13 02:40:38 -04:00
if ( _debug > 1 & & _perf_counters & & _perf_counters [ i ] ) {
hal . util - > perf_begin ( _perf_counters [ i ] ) ;
}
_tasks [ i ] . function ( ) ;
if ( _debug > 1 & & _perf_counters & & _perf_counters [ i ] ) {
hal . util - > perf_end ( _perf_counters [ i ] ) ;
}
2019-05-09 07:47:10 -03:00
hal . util - > persistent_data . scheduler_task = - 1 ;
2018-02-13 02:40:38 -04:00
// record the tick counter when we ran. This drives
// when we next run the event
_last_run [ i ] = _tick_counter ;
// work out how long the event actually took
now = AP_HAL : : micros ( ) ;
uint32_t time_taken = now - _task_time_started ;
if ( time_taken > _task_time_allowed ) {
// the event overran!
debug ( 3 , " Scheduler overrun task[%u-%s] (%u/%u) \n " ,
( unsigned ) i ,
_tasks [ i ] . name ,
( unsigned ) time_taken ,
( unsigned ) _task_time_allowed ) ;
}
if ( time_taken > = time_available ) {
2018-02-13 03:02:47 -04:00
time_available = 0 ;
break ;
2013-01-11 20:59:20 -04:00
}
2018-02-13 02:40:38 -04:00
time_available - = time_taken ;
2013-01-11 20:59:20 -04:00
}
2013-07-23 02:00:00 -03:00
// update number of spare microseconds
_spare_micros + = time_available ;
_spare_ticks + + ;
if ( _spare_ticks = = 32 ) {
_spare_ticks / = 2 ;
_spare_micros / = 2 ;
}
2013-01-11 20:59:20 -04:00
}
/*
return number of micros until the current task reaches its deadline
*/
uint16_t AP_Scheduler : : time_available_usec ( void )
{
2015-11-19 23:14:32 -04:00
uint32_t dt = AP_HAL : : micros ( ) - _task_time_started ;
2013-01-11 20:59:20 -04:00
if ( dt > _task_time_allowed ) {
return 0 ;
}
return _task_time_allowed - dt ;
}
2013-07-23 02:00:00 -03:00
/*
calculate load average as a number from 0 to 1
*/
2018-01-17 03:20:44 -04:00
float AP_Scheduler : : load_average ( )
2013-07-23 02:00:00 -03:00
{
2013-08-02 09:07:00 -03:00
if ( _spare_ticks = = 0 ) {
return 0.0f ;
}
2017-07-30 02:02:40 -03:00
const uint32_t loop_us = get_loop_period_us ( ) ;
const uint32_t used_time = loop_us - ( _spare_micros / _spare_ticks ) ;
return used_time / ( float ) loop_us ;
2013-07-23 02:00:00 -03:00
}
2017-11-13 03:11:27 -04:00
void AP_Scheduler : : loop ( )
{
// wait for an INS sample
2019-05-16 20:00:22 -03:00
hal . util - > persistent_data . scheduler_task = - 3 ;
2017-11-13 03:11:27 -04:00
AP : : ins ( ) . wait_for_sample ( ) ;
2019-05-16 20:00:22 -03:00
hal . util - > persistent_data . scheduler_task = - 1 ;
2017-11-13 03:11:27 -04:00
2018-02-09 22:09:09 -04:00
const uint32_t sample_time_us = AP_HAL : : micros ( ) ;
2018-02-11 23:42:54 -04:00
if ( _loop_timer_start_us = = 0 ) {
_loop_timer_start_us = sample_time_us ;
_last_loop_time_s = get_loop_period_s ( ) ;
} else {
_last_loop_time_s = ( sample_time_us - _loop_timer_start_us ) * 1.0e-6 ;
2018-02-09 22:09:09 -04:00
}
2017-11-13 03:11:27 -04:00
// Execute the fast loop
// ---------------------
if ( _fastloop_fn ) {
2019-05-09 07:47:10 -03:00
hal . util - > persistent_data . scheduler_task = - 2 ;
2017-11-13 03:11:27 -04:00
_fastloop_fn ( ) ;
2019-05-09 07:47:10 -03:00
hal . util - > persistent_data . scheduler_task = - 1 ;
2017-11-13 03:11:27 -04:00
}
2019-09-17 05:13:28 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
{
/*
for testing low CPU conditions we can add an optional delay in SITL
*/
auto * sitl = AP : : sitl ( ) ;
uint32_t loop_delay_us = sitl - > loop_delay . get ( ) ;
hal . scheduler - > delay_microseconds ( loop_delay_us ) ;
}
# endif
2017-11-13 03:11:27 -04:00
// tell the scheduler one tick has passed
tick ( ) ;
// run all the tasks that are due to run. Note that we only
// have to call this once per loop, as the tasks are scheduled
// in multiples of the main loop tick. So if they don't run on
// the first call to the scheduler they won't run on a later
// call until scheduler.tick() is called again
const uint32_t loop_us = get_loop_period_us ( ) ;
2019-09-17 05:13:28 -03:00
uint32_t now = AP_HAL : : micros ( ) ;
uint32_t time_available = 0 ;
if ( now - sample_time_us < loop_us ) {
// get remaining time available for this loop
time_available = loop_us - ( now - sample_time_us ) ;
}
// add in extra loop time determined by not achieving scheduler tasks
time_available + = extra_loop_us ;
// run the tasks
run ( time_available ) ;
2017-11-13 05:52:17 -04:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// move result of AP_HAL::micros() forward:
hal . scheduler - > delay_microseconds ( 1 ) ;
# endif
2018-02-09 22:09:09 -04:00
2019-09-17 05:13:28 -03:00
if ( task_not_achieved > 0 ) {
// add some extra time to the budget
extra_loop_us = MIN ( extra_loop_us + 100U , 5000U ) ;
task_not_achieved = 0 ;
task_all_achieved = 0 ;
} else if ( extra_loop_us > 0 ) {
task_all_achieved + + ;
if ( task_all_achieved > 50 ) {
// we have gone through 50 loops without a task taking too
// long. CPU pressure has eased, so drop the extra time we're
// giving each loop
task_all_achieved = 0 ;
// we are achieving all tasks, slowly lower the extra loop time
extra_loop_us = MAX ( 0U , extra_loop_us - 50U ) ;
}
}
2018-02-09 22:47:16 -04:00
// check loop time
2018-02-11 23:42:54 -04:00
perf_info . check_loop_time ( sample_time_us - _loop_timer_start_us ) ;
2018-02-09 22:47:16 -04:00
2018-02-11 23:42:54 -04:00
_loop_timer_start_us = sample_time_us ;
2017-11-13 03:11:27 -04:00
}
2017-11-13 04:25:54 -04:00
2018-02-09 18:38:17 -04:00
void AP_Scheduler : : update_logging ( )
2017-11-13 04:25:54 -04:00
{
2018-02-08 21:47:24 -04:00
if ( debug_flags ( ) ) {
2017-11-13 04:25:54 -04:00
perf_info . update_logging ( ) ;
}
2018-02-09 18:38:17 -04:00
if ( _log_performance_bit ! = ( uint32_t ) - 1 & &
2019-01-18 00:24:08 -04:00
AP : : logger ( ) . should_log ( _log_performance_bit ) ) {
2017-11-15 23:20:04 -04:00
Log_Write_Performance ( ) ;
}
perf_info . set_loop_rate ( get_loop_rate_hz ( ) ) ;
perf_info . reset ( ) ;
}
// Write a performance monitoring packet
void AP_Scheduler : : Log_Write_Performance ( )
{
2019-05-16 04:58:07 -03:00
const AP_HAL : : Util : : PersistentData & pd = hal . util - > persistent_data ;
2017-11-15 23:20:04 -04:00
struct log_Performance pkt = {
LOG_PACKET_HEADER_INIT ( LOG_PERFORMANCE_MSG ) ,
time_us : AP_HAL : : micros64 ( ) ,
num_long_running : perf_info . get_num_long_running ( ) ,
num_loops : perf_info . get_num_loops ( ) ,
max_time : perf_info . get_max_time ( ) ,
2018-02-15 11:58:08 -04:00
mem_avail : hal . util - > available_memory ( ) ,
2018-08-07 06:59:37 -03:00
load : ( uint16_t ) ( load_average ( ) * 1000 ) ,
2019-05-16 04:58:07 -03:00
internal_errors : AP : : internalerror ( ) . errors ( ) ,
2019-06-03 01:17:20 -03:00
internal_error_count : AP : : internalerror ( ) . count ( ) ,
2019-05-16 04:58:07 -03:00
spi_count : pd . spi_count ,
i2c_count : pd . i2c_count ,
2019-08-25 04:47:19 -03:00
i2c_isr_count : pd . i2c_isr_count ,
2019-09-17 05:13:28 -03:00
extra_loop_us : extra_loop_us ,
2017-11-15 23:20:04 -04:00
} ;
2019-01-18 00:24:08 -04:00
AP : : logger ( ) . WriteCriticalBlock ( & pkt , sizeof ( pkt ) ) ;
2017-11-13 04:25:54 -04:00
}
2018-05-03 21:44:50 -03:00
namespace AP {
AP_Scheduler & scheduler ( )
{
2019-02-10 01:03:20 -04:00
return * AP_Scheduler : : get_singleton ( ) ;
2018-05-03 21:44:50 -03:00
}
} ;