|
MAV'RIC
|
Task entry. More...
#include <scheduler_task.hpp>
Classes | |
| struct | function |
| Prototype of a task function and its argument. More... | |
Public Types | |
| enum | return_t { RUN_ERROR = -1, RUN_BLOCKED = 0, RUN_SUCCESS = 1 } |
| Task return code. More... | |
| enum | run_mode_t { RUN_NEVER, RUN_ONCE, RUN_REGULAR } |
| Task run mode. More... | |
| enum | timing_mode_t { PERIODIC_ABSOLUTE, PERIODIC_RELATIVE } |
| Task timing mode. More... | |
| enum | priority_t { PRIORITY_LOWEST = 0, PRIORITY_LOW = 1, PRIORITY_NORMAL = 2, PRIORITY_HIGH = 3, PRIORITY_HIGHEST = 4 } |
| Task priority. More... | |
Public Member Functions | |
| Scheduler_task (void) | |
| Default Constructor. | |
| template<typename T > | |
| Scheduler_task (uint32_t repeat_period, run_mode_t run_mode, timing_mode_t timing_mode, priority_t priority, typename function< T >::type_t task_function, T *task_argument, int32_t task_id) | |
| Constructor. | |
| void | set_run_mode (run_mode_t mode) |
| Modifies the run mode of an existing task. | |
| void | run_now () |
| Run a task immediately. | |
| void | suspend (uint32_t delay) |
| Suspends a task. | |
| void | change_period (uint32_t repeat_period) |
| Modifies the period of execution of an existing task. | |
| int32_t | get_id () |
| Returns the ID of the task. | |
| bool | execute () |
| Executes tasks and updates statistics. | |
| bool | is_due () |
| Checks if the task is due. | |
Public Attributes | |
| int32_t | task_id |
| Unique task identifier. | |
| run_mode_t | run_mode |
| Run mode. | |
| timing_mode_t | timing_mode |
| Timing mode. | |
| priority_t | priority |
| Priority. | |
| uint32_t | repeat_period |
| Period between two calls (us) | |
| uint32_t | next_run |
| Next execution time. | |
| float | execution_time |
| Execution time. | |
| float | execution_time_avg |
| Average execution time. | |
| float | execution_time_var |
| Variance of execution time. | |
| float | execution_time_max |
| Maximum execution time. | |
| float | delay |
| Delay between expected execution and actual execution. | |
| float | delay_avg |
| Average delay. | |
| float | delay_var |
| Variance of delay. | |
| float | delay_max |
| Maximum delay. | |
| uint32_t | rt_violations |
| Number of Real-time violations, this is incremented each time an execution is skipped. | |
Task entry.
| Scheduler_task::Scheduler_task | ( | uint32_t | repeat_period, |
| run_mode_t | run_mode, | ||
| timing_mode_t | timing_mode, | ||
| priority_t | priority, | ||
| typename function< T >::type_t | task_function, | ||
| T * | task_argument, | ||
| int32_t | task_id | ||
| ) |
Constructor.
| T | Type of the module |
| repeat_period | Repeat period in us |
| run_mode | Run mode, defined in enum Scheduler_task::run_mode_t |
| timing_mode | Timing mode, defined in Scheduler_task::timing_mode_t |
| priority | Priority ,defined in Scheduler_task::priority_t |
| task_function | Function to call |
| task_argument | Argument of the funtion to call |
| task_id | ID of the task |
| void Scheduler_task::change_period | ( | uint32_t | repeat_period | ) |
Modifies the period of execution of an existing task.
| repeat_period | New repeat period (us) |


| bool Scheduler_task::execute | ( | ) |
Executes tasks and updates statistics.
| int32_t Scheduler_task::get_id | ( | ) |
Returns the ID of the task.
| bool Scheduler_task::is_due | ( | ) |
Checks if the task is due.
| void Scheduler_task::set_run_mode | ( | run_mode_t | mode | ) |
Modifies the run mode of an existing task.
| new_run_mode | New run mode |

| void Scheduler_task::suspend | ( | uint32_t | delay | ) |
Suspends a task.
| delay | Duration (us) |

1.7.6.1