MAV'RIC
Classes | Public Types | Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions
Scheduler Class Reference

Scheduler base class. More...

#include <scheduler.hpp>

Inheritance diagram for Scheduler:
Inheritance graph
[legend]

List of all members.

Classes

struct  conf_t
 Scheduler configuration. More...

Public Types

enum  strategy_t { ROUND_ROBIN, FIXED_PRIORITY }
 Scheduling strategy. More...

Public Member Functions

 Scheduler (const Scheduler::conf_t config=default_config())
 Constructor.
template<typename T >
bool add_task (uint32_t repeat_period, typename Scheduler_task::function< T >::type_t task_function, T *task_argument, Scheduler_task::priority_t priority=Scheduler_task::PRIORITY_NORMAL, Scheduler_task::timing_mode_t timing_mode=Scheduler_task::PERIODIC_ABSOLUTE, Scheduler_task::run_mode_t run_mode=Scheduler_task::RUN_REGULAR, int32_t task_id=-1)
 Register a new task to the task set, in the first available slot.
bool sort_tasks (void)
 Sort tasks by decreasing priority, then by increasing repeat period.
int32_t update (void)
 Run update (check for tasks ready for execution and execute them)
const Scheduler_taskget_task_by_id (uint16_t task_id) const
 Find a task according to its idea.
Scheduler_taskget_task_by_id (uint16_t task_id)
const Scheduler_taskget_task_by_index (uint16_t task_index) const
 Find a task according to its index.
Scheduler_taskget_task_by_index (uint16_t task_index)
void suspend_all_tasks (uint32_t delay)
 Suspends all tasks.
void run_all_tasks_now (void)
 Run all tasks immediately.
uint32_t task_count (void) const
 Return the number of tasks.

Static Public Member Functions

static Scheduler::conf_t default_config (void)
 Creates and returns default config for schedulers.

Static Public Attributes

static const uint32_t TIMEBASE = 1000000
 < time base for the scheduler

Protected Member Functions

virtual uint32_t max_task_count (void)=0
 Get maximum number of tasks.
virtual Scheduler_tasktasks (void)=0
 Get pointer to the task list.
virtual const Scheduler_tasktasks (void) const =0

Detailed Description

Scheduler base class.

This class is abstract and does not contains the task list, use the child class Scheduler_T


Member Enumeration Documentation

Scheduling strategy.

Enumerator:
ROUND_ROBIN 

Round robin scheduling.

FIXED_PRIORITY 

Fixed priority scheduling.


Constructor & Destructor Documentation

Constructor.

Parameters:
configConfiguration

Member Function Documentation

template<typename T >
bool Scheduler::add_task ( uint32_t  repeat_period,
typename Scheduler_task::function< T >::type_t  task_function,
T *  task_argument,
Scheduler_task::priority_t  priority = Scheduler_task::PRIORITY_NORMAL,
Scheduler_task::timing_mode_t  timing_mode = Scheduler_task::PERIODIC_ABSOLUTE,
Scheduler_task::run_mode_t  run_mode = Scheduler_task::RUN_REGULAR,
int32_t  task_id = -1 
)

Register a new task to the task set, in the first available slot.

Parameters:
repeat_periodRepeat period (us)
task_functionFunction pointer to be called
task_argumentArgument to be passed to the function
priorityPriority
task_idUnique task identifier, if -1 the ID will be automatically chosen
timing_modeTiming mode
run_modeRun mode
Returns:
True if the task was successfully added, False if not

Here is the call graph for this function:

Here is the caller graph for this function:

Creates and returns default config for schedulers.

Returns:
default_config
const Scheduler_task * Scheduler::get_task_by_id ( uint16_t  task_id) const

Find a task according to its idea.

Parameters:
task_idID of the target task
Returns:
Pointer to the target task

Here is the call graph for this function:

Here is the caller graph for this function:

const Scheduler_task * Scheduler::get_task_by_index ( uint16_t  task_index) const

Find a task according to its index.

Parameters:
task_indexIndex of the target task
Returns:
Pointer to the target task

Here is the call graph for this function:

virtual uint32_t Scheduler::max_task_count ( void  ) [protected, pure virtual]

Get maximum number of tasks.

To be overriden by child class

Returns:
Maximum number of tasks

Implemented in Scheduler_T< N >, and Scheduler_T< 20 >.

Here is the caller graph for this function:

bool Scheduler::sort_tasks ( void  )

Sort tasks by decreasing priority, then by increasing repeat period.

Returns:
True if the task was successfully sorted, False if not

Here is the call graph for this function:

Here is the caller graph for this function:

void Scheduler::suspend_all_tasks ( uint32_t  delay)

Suspends all tasks.

Parameters:
delayDuration (us)

Here is the call graph for this function:

virtual Scheduler_task* Scheduler::tasks ( void  ) [protected, pure virtual]

Get pointer to the task list.

Abstract method to be implemented in child classes

Returns:
task list

Implemented in Scheduler_T< N >, and Scheduler_T< 20 >.

Here is the caller graph for this function:

int32_t Scheduler::update ( void  )

Run update (check for tasks ready for execution and execute them)

Returns:
Number of realtime violations

Here is the call graph for this function:

Here is the caller graph for this function:


The documentation for this class was generated from the following files:
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines