MAV'RIC
Classes | Public Member Functions | Static Public Member Functions | Protected Member Functions
Periodic_telemetry Class Reference
Inheritance diagram for Periodic_telemetry:
Inheritance graph
[legend]

List of all members.

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 Schedulerscheduler (void)=0
 Get reference to scheduler.
virtual telemetry_entry_tlist (void)=0
 Get pointer to list of telemetry items.

Constructor & Destructor Documentation

Constructor.

Parameters:
mavlink_streamStream to which messages will be written
message_handlerMAVLink message handler
configConfiguration structure

Here is the call graph for this function:


Member Function Documentation

template<typename T >
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.

Template Parameters:
TType of the module
Parameters:
task_idUnique task identifier
repeat_periodRepeat period (us)
telemetry_functionFunction pointer to be called
telemetry_moduleArgument to be passed to the function
priorityPriority
timing_modeTiming mode
run_modeRun mode
Returns:
True if the message was correctly added, false otherwise

Here is the call graph for this function:

Default configuration structure.

Returns:
Config
virtual telemetry_entry_t* Periodic_telemetry::list ( void  ) [protected, pure virtual]

Get pointer to list of telemetry items.

To be overriden by child class

Returns:
list

Implemented in Periodic_telemetry_T< N >, and Periodic_telemetry_T< N_TELEM >.

Here is the caller graph for this function:

virtual uint32_t Periodic_telemetry::max_count ( void  ) [protected, pure virtual]

Get maximum number of telemetry messages.

To be overriden by child class

Returns:
Maximum number

Implemented in Periodic_telemetry_T< N >, and Periodic_telemetry_T< N_TELEM >.

Here is the caller graph for this function:

virtual Scheduler& Periodic_telemetry::scheduler ( void  ) [protected, pure virtual]

Get reference to scheduler.

To be overriden by child class

Returns:
Scheduler

Implemented in Periodic_telemetry_T< N >, and Periodic_telemetry_T< N_TELEM >.

Here is the caller graph for this function:

bool Periodic_telemetry::sort ( void  )

Sort telemetry items 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 Periodic_telemetry::toggle_telemetry_stream ( Periodic_telemetry scheduler,
uint32_t  sysid,
const mavlink_message_t *  msg 
) [static]

Toggle mavlink telemetry stream.

Parameters:
schedulerscheduler of the MAV
sysidMAV sysid
msgpointer to the stream you want to toggle

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