MAV'RIC
|
Classes | |
struct | conf_t |
Configuration structure. More... | |
struct | function |
Prototype of telemetry functions. More... | |
struct | telemetry_entry_t |
MAVLink message handler structure. More... | |
Public Member Functions | |
Periodic_telemetry (Mavlink_stream &mavlink_stream, Mavlink_message_handler &handler, conf_t config=default_config()) | |
Constructor. | |
bool | update (void) |
Main update function. | |
template<typename T > | |
bool | add (uint32_t task_id, uint32_t repeat_period, typename function< T >::type_t telemetry_function, T *telemetry_module, Scheduler_task::priority_t priority=Scheduler_task::PRIORITY_NORMAL, Scheduler_task::timing_mode_t timing_mode=Scheduler_task::PERIODIC_RELATIVE, Scheduler_task::run_mode_t run_mode=Scheduler_task::RUN_REGULAR) |
Add new telemetry message to the scheduler. | |
bool | sort (void) |
Sort telemetry items by decreasing priority, then by increasing repeat period. | |
Static Public Member Functions | |
static conf_t | default_config (void) |
Default configuration structure. | |
static void | toggle_telemetry_stream (Periodic_telemetry *scheduler, uint32_t sysid, const mavlink_message_t *msg) |
Toggle mavlink telemetry stream. | |
Protected Member Functions | |
virtual uint32_t | max_count (void)=0 |
Get maximum number of telemetry messages. | |
virtual Scheduler & | scheduler (void)=0 |
Get reference to scheduler. | |
virtual telemetry_entry_t * | list (void)=0 |
Get pointer to list of telemetry items. |
Periodic_telemetry::Periodic_telemetry | ( | Mavlink_stream & | mavlink_stream, |
Mavlink_message_handler & | handler, | ||
conf_t | config = default_config() |
||
) |
Constructor.
mavlink_stream | Stream to which messages will be written |
message_handler | MAVLink message handler |
config | Configuration structure |
bool Periodic_telemetry::add | ( | uint32_t | task_id, |
uint32_t | repeat_period, | ||
typename function< T >::type_t | telemetry_function, | ||
T * | telemetry_module, | ||
Scheduler_task::priority_t | priority = Scheduler_task::PRIORITY_NORMAL , |
||
Scheduler_task::timing_mode_t | timing_mode = Scheduler_task::PERIODIC_RELATIVE , |
||
Scheduler_task::run_mode_t | run_mode = Scheduler_task::RUN_REGULAR |
||
) |
Add new telemetry message to the scheduler.
T | Type of the module |
task_id | Unique task identifier |
repeat_period | Repeat period (us) |
telemetry_function | Function pointer to be called |
telemetry_module | Argument to be passed to the function |
priority | Priority |
timing_mode | Timing mode |
run_mode | Run mode |
Periodic_telemetry::conf_t Periodic_telemetry::default_config | ( | void | ) | [inline, static] |
Default configuration structure.
virtual telemetry_entry_t* Periodic_telemetry::list | ( | void | ) | [protected, pure virtual] |
Get pointer to list of telemetry items.
To be overriden by child class
Implemented in Periodic_telemetry_T< N >, and Periodic_telemetry_T< N_TELEM >.
virtual uint32_t Periodic_telemetry::max_count | ( | void | ) | [protected, pure virtual] |
Get maximum number of telemetry messages.
To be overriden by child class
Implemented in Periodic_telemetry_T< N >, and Periodic_telemetry_T< N_TELEM >.
virtual Scheduler& Periodic_telemetry::scheduler | ( | void | ) | [protected, pure virtual] |
Get reference to scheduler.
To be overriden by child class
Implemented in Periodic_telemetry_T< N >, and Periodic_telemetry_T< N_TELEM >.
bool Periodic_telemetry::sort | ( | void | ) |
Sort telemetry items by decreasing priority, then by increasing repeat period.
void Periodic_telemetry::toggle_telemetry_stream | ( | Periodic_telemetry * | scheduler, |
uint32_t | sysid, | ||
const mavlink_message_t * | msg | ||
) | [static] |