|
MAV'RIC
|
#include <scheduler.hpp>

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_task * | get_task_by_id (uint16_t task_id) const |
| Find a task according to its idea. | |
| Scheduler_task * | get_task_by_id (uint16_t task_id) |
| const Scheduler_task * | get_task_by_index (uint16_t task_index) const |
| Find a task according to its index. | |
| Scheduler_task * | get_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_task * | tasks (void)=0 |
| Get pointer to the task list. | |
| virtual const Scheduler_task * | tasks (void) const =0 |
Scheduler base class.
This class is abstract and does not contains the task list, use the child class Scheduler_T
| Scheduler::Scheduler | ( | const Scheduler::conf_t | config = default_config() | ) |
Constructor.
| config | Configuration |
| 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.
| repeat_period | Repeat period (us) |
| task_function | Function pointer to be called |
| task_argument | Argument to be passed to the function |
| priority | Priority |
| task_id | Unique task identifier, if -1 the ID will be automatically chosen |
| timing_mode | Timing mode |
| run_mode | Run mode |


| Scheduler::conf_t Scheduler::default_config | ( | void | ) | [static] |
Creates and returns default config for schedulers.
| const Scheduler_task * Scheduler::get_task_by_id | ( | uint16_t | task_id | ) | const |
Find a task according to its idea.
| task_id | ID of the target task |


| const Scheduler_task * Scheduler::get_task_by_index | ( | uint16_t | task_index | ) | const |
Find a task according to its index.
| task_index | Index of the target task |

| virtual uint32_t Scheduler::max_task_count | ( | void | ) | [protected, pure virtual] |
Get maximum number of tasks.
To be overriden by child class
Implemented in Scheduler_T< N >, and Scheduler_T< 20 >.

| bool Scheduler::sort_tasks | ( | void | ) |
Sort tasks by decreasing priority, then by increasing repeat period.


| void Scheduler::suspend_all_tasks | ( | uint32_t | delay | ) |
Suspends all tasks.
| delay | Duration (us) |

| virtual Scheduler_task* Scheduler::tasks | ( | void | ) | [protected, pure virtual] |
Get pointer to the task list.
Abstract method to be implemented in child classes
Implemented in Scheduler_T< N >, and Scheduler_T< 20 >.

| int32_t Scheduler::update | ( | void | ) |
Run update (check for tasks ready for execution and execute them)


1.7.6.1