MAV'RIC
Classes | Public Member Functions | Static Public Member Functions
Mavlink_communication_T< N_TELEM, N_MSG_CB, N_CMD_CB, N_PARAM > Class Template Reference

Handles various aspect of mavlink protocol with periodic telemetry, message callback, and onboard parameters. More...

#include <mavlink_communication.hpp>

List of all members.

Classes

struct  conf_t
 Configuration of the module Mavlink Communication. More...

Public Member Functions

 Mavlink_communication_T (Serial &serial, State &state, File &file_storage, const conf_t &config=default_config())
 Initialisation of the module MAVLink communication.
uint32_t sysid ()
 Returns sysid of the underlying mavlink_stream.
Periodic_telemetrytelemetry ()
Mavlink_message_handlerhandler ()
Mavlink_streammavlink_stream ()
Onboard_parametersparameters ()
bool update (void)
 Main update function.

Static Public Member Functions

static conf_t default_config (uint8_t sysid=1)
 Default configuration.
static bool update_task (Mavlink_communication_T *mavlink_communication)
 Main update function, static version.

Detailed Description

template<uint32_t N_TELEM, uint32_t N_MSG_CB, uint32_t N_CMD_CB, uint32_t N_PARAM>
class Mavlink_communication_T< N_TELEM, N_MSG_CB, N_CMD_CB, N_PARAM >

Handles various aspect of mavlink protocol with periodic telemetry, message callback, and onboard parameters.


Constructor & Destructor Documentation

template<uint32_t N_TELEM, uint32_t N_MSG_CB, uint32_t N_CMD_CB, uint32_t N_PARAM>
Mavlink_communication_T< N_TELEM, N_MSG_CB, N_CMD_CB, N_PARAM >::Mavlink_communication_T ( Serial serial,
State state,
File file_storage,
const conf_t config = default_config() 
) [inline]

Initialisation of the module MAVLink communication.

Parameters:
configConfiguration
serialInput/Output stream
stateMAV state
file_storageFile used to store parameters between files
Returns:
True if the init succeed, false otherwise

Member Function Documentation

template<uint32_t N_TELEM, uint32_t N_MSG_CB, uint32_t N_CMD_CB, uint32_t N_PARAM>
static conf_t Mavlink_communication_T< N_TELEM, N_MSG_CB, N_CMD_CB, N_PARAM >::default_config ( uint8_t  sysid = 1) [inline, static]

Default configuration.

Parameters:
sysidSystem id (default value = 1)
Returns:
Config structure

Here is the call graph for this function:

Here is the caller graph for this function:

template<uint32_t N_TELEM, uint32_t N_MSG_CB, uint32_t N_CMD_CB, uint32_t N_PARAM>
uint32_t Mavlink_communication_T< N_TELEM, N_MSG_CB, N_CMD_CB, N_PARAM >::sysid ( ) [inline]

Returns sysid of the underlying mavlink_stream.

Returns:
sysid of the underlying mavlink_stream

Here is the call graph for this function:

Here is the caller graph for this function:

template<uint32_t N_TELEM, uint32_t N_MSG_CB, uint32_t N_CMD_CB, uint32_t N_PARAM>
bool Mavlink_communication_T< N_TELEM, N_MSG_CB, N_CMD_CB, N_PARAM >::update ( void  ) [inline]

Main update function.

Returns:
Success

Here is the call graph for this function:

Here is the caller graph for this function:

template<uint32_t N_TELEM, uint32_t N_MSG_CB, uint32_t N_CMD_CB, uint32_t N_PARAM>
static bool Mavlink_communication_T< N_TELEM, N_MSG_CB, N_CMD_CB, N_PARAM >::update_task ( Mavlink_communication_T< N_TELEM, N_MSG_CB, N_CMD_CB, N_PARAM > *  mavlink_communication) [inline, static]

Main update function, static version.

Parameters:
mavlink_communicationPointer to the MAVLink communication structure
Returns:
Success

Here is the call graph for this function:


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