@ -57,6 +57,13 @@ const AP_Param::GroupInfo AP_Scheduler::var_info[] = {
@@ -57,6 +57,13 @@ const AP_Param::GroupInfo AP_Scheduler::var_info[] = {
// @User: Advanced
AP_GROUPINFO ( " LOOP_RATE " , 1 , AP_Scheduler , _loop_rate_hz , SCHEDULER_DEFAULT_LOOP_RATE ) ,
// @Param: OPTIONS
// @DisplayName: Scheduling options
// @Description: This controls optional aspects of the scheduler.
// @Bitmask: 0:Enable per-task perf info
// @User: Advanced
AP_GROUPINFO ( " OPTIONS " , 2 , AP_Scheduler , _options , 0 ) ,
AP_GROUPEND
} ;
@ -114,6 +121,10 @@ void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks, uint
@@ -114,6 +121,10 @@ void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks, uint
perf_info . set_loop_rate ( get_loop_rate_hz ( ) ) ;
perf_info . reset ( ) ;
if ( _options & uint8_t ( Options : : RECORD_TASK_INFO ) ) {
perf_info . allocate_task_info ( _num_tasks ) ;
}
_log_performance_bit = log_performance_bit ;
}
@ -173,13 +184,7 @@ void AP_Scheduler::run(uint32_t time_available)
@@ -173,13 +184,7 @@ void AP_Scheduler::run(uint32_t time_available)
_task_time_allowed = task . 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 ,
task . name ,
( unsigned ) dt ,
( unsigned ) interval_ticks ,
( unsigned ) _task_time_allowed ) ;
perf_info . task_slipped ( i ) ;
}
if ( dt > = interval_ticks * max_task_slowdown ) {
@ -216,8 +221,9 @@ void AP_Scheduler::run(uint32_t time_available)
@@ -216,8 +221,9 @@ void AP_Scheduler::run(uint32_t time_available)
// work out how long the event actually took
now = AP_HAL : : micros ( ) ;
uint32_t time_taken = now - _task_time_started ;
bool overrun = false ;
if ( time_taken > _task_time_allowed ) {
overrun = true ;
// the event overran!
debug ( 3 , " Scheduler overrun task[%u-%s] (%u/%u) \n " ,
( unsigned ) i ,
@ -225,6 +231,9 @@ void AP_Scheduler::run(uint32_t time_available)
@@ -225,6 +231,9 @@ void AP_Scheduler::run(uint32_t time_available)
( unsigned ) time_taken ,
( unsigned ) _task_time_allowed ) ;
}
perf_info . update_task_info ( i , time_taken , overrun ) ;
if ( time_taken > = time_available ) {
time_available = 0 ;
break ;
@ -365,6 +374,12 @@ void AP_Scheduler::update_logging()
@@ -365,6 +374,12 @@ void AP_Scheduler::update_logging()
}
perf_info . set_loop_rate ( get_loop_rate_hz ( ) ) ;
perf_info . reset ( ) ;
// dynamically update the per-task perf counter
if ( ! ( _options & uint8_t ( Options : : RECORD_TASK_INFO ) ) & & perf_info . has_task_info ( ) ) {
perf_info . free_task_info ( ) ;
} else if ( ( _options & uint8_t ( Options : : RECORD_TASK_INFO ) ) & & ! perf_info . has_task_info ( ) ) {
perf_info . allocate_task_info ( _num_tasks ) ;
}
}
// Write a performance monitoring packet
@ -389,6 +404,61 @@ void AP_Scheduler::Log_Write_Performance()
@@ -389,6 +404,61 @@ void AP_Scheduler::Log_Write_Performance()
AP : : logger ( ) . WriteCriticalBlock ( & pkt , sizeof ( pkt ) ) ;
}
// display task statistics as text buffer for @SYS/tasks.txt
size_t AP_Scheduler : : task_info ( char * buf , size_t bufsize )
{
size_t total = 0 ;
// a header to allow for machine parsers to determine format
int n = hal . util - > snprintf ( buf , bufsize , " TasksV1 \n " ) ;
if ( n < = 0 ) {
return 0 ;
}
// dynamically enable statistics collection
if ( ! ( _options & uint8_t ( Options : : RECORD_TASK_INFO ) ) ) {
_options | = uint8_t ( Options : : RECORD_TASK_INFO ) ;
return n ;
}
if ( perf_info . get_task_info ( 0 ) = = nullptr ) {
return n ;
}
buf + = n ;
bufsize - = n ;
total + = n ;
for ( uint8_t i = 0 ; i < _num_tasks ; i + + ) {
const AP_Scheduler : : Task & task = ( i < _num_unshared_tasks ) ? _tasks [ i ] : _common_tasks [ i - _num_unshared_tasks ] ;
const AP : : PerfInfo : : TaskInfo * ti = perf_info . get_task_info ( i ) ;
uint16_t avg = 0 ;
if ( ti - > tick_count > 0 ) {
avg = MIN ( uint16_t ( ti - > elapsed_time_us / ti - > tick_count ) , 999 ) ;
}
# if HAL_MINIMIZE_FEATURES
const char * fmt = " %-16.16s MIN=%3u MAX=%3u AVG=%3u OVR=%3u SLP=%3u \n " ;
# else
const char * fmt = " %-32.32s MIN=%3u MAX=%3u AVG=%3u OVR=%3u SLP=%3u \n " ;
# endif
n = hal . util - > snprintf ( buf , bufsize , fmt , task . name ,
unsigned ( MIN ( ti - > min_time_us , 999 ) ) , unsigned ( MIN ( ti - > max_time_us , 999 ) ) , unsigned ( avg ) ,
unsigned ( MIN ( ti - > overrun_count , 999 ) ) , unsigned ( MIN ( ti - > slip_count , 999 ) ) ) ;
if ( n < = 0 ) {
break ;
}
buf + = n ;
bufsize - = n ;
total + = n ;
}
return total ;
}
namespace AP {
AP_Scheduler & scheduler ( )