|
MAV'RIC
|
Message handler base class. More...
#include <mavlink_message_handler.hpp>

Classes | |
| struct | cmd_callback_t |
| Command callback. More... | |
| struct | cmd_function |
| Prototype of function callback for mavlink commands. More... | |
| struct | conf_t |
| Structure used to hold parameters during initialisation. More... | |
| struct | msg_callback_t |
| Message callback. More... | |
| struct | msg_function |
| Prototype of function callback for mavlink messages. More... | |
Public Types | |
| typedef enum MAV_COMPONENT | mav_component_t |
| Enumeration of MAV components. | |
Public Member Functions | |
| Mavlink_message_handler (Mavlink_stream &mavlink_stream, const conf_t &config) | |
| Constructor. | |
| template<typename T > | |
| bool | add_msg_callback (uint8_t message_id, uint8_t sysid_filter, mav_component_t compid_filter, typename msg_function< T >::type_t function, T *module_struct) |
| Registers a new callback for a message. | |
| template<typename T > | |
| bool | add_cmd_callback (uint16_t command_id, uint8_t sysid_filter, mav_component_t compid_filter, mav_component_t compid_target, typename cmd_function< T >::type_t function, T *module_struct) |
| Registers a new callback for a command. | |
| void | receive (Mavlink_stream::msg_received_t *rec) |
| Main update function, handles the incoming message according to the registered message and command callbacks. | |
Static Public Member Functions | |
| static conf_t | default_config (void) |
| Default configuration. | |
| static void | msg_default_dbg (mavlink_message_t *msg) |
| Dummy message callback for debug purpose. | |
| static void | cmd_default_dbg (mavlink_command_long_t *cmd) |
| Dummy command callback for debug purpose. | |
Protected Member Functions | |
| virtual uint32_t | msg_callback_max_count (void)=0 |
| Get maximum number of message callbacks. | |
| virtual uint32_t | cmd_callback_max_count (void)=0 |
| Get maximum number of command callbacks. | |
| virtual msg_callback_t * | msg_callback_list (void)=0 |
| Get list of message callbacks. | |
| virtual cmd_callback_t * | cmd_callback_list (void)=0 |
| Get list of command callbacks. | |
Message handler base class.
This class is abstract and does not contains the lists of handlers, use the child class Mavlink_message_handler_T
| typedef enum MAV_COMPONENT Mavlink_message_handler::mav_component_t |
Enumeration of MAV components.
The enumeration MAV_COMPONENT is defined by MAVLink
| Mavlink_message_handler::Mavlink_message_handler | ( | Mavlink_stream & | mavlink_stream, |
| const conf_t & | config | ||
| ) |
Constructor.
| config | Config parameters |
| mavlink_stream | mavlink stream |
| bool Mavlink_message_handler::add_cmd_callback | ( | uint16_t | command_id, |
| uint8_t | sysid_filter, | ||
| mav_component_t | compid_filter, | ||
| mav_component_t | compid_target, | ||
| typename cmd_function< T >::type_t | function, | ||
| T * | module_struct | ||
| ) |
Registers a new callback for a command.
You should call mavlink_message_handler_sort_callback function after having added all callbacks, as it is used by mavlink_message_handler_receive to speed up matching
| command_id | The function will be called only for commands with ID command_id |
| sysid_filter | The function will be called only for commands coming from MAVs with ID sysid_filter (0 for all) |
| compid_filter | The function will be called only for commands coming from component compid_filter (0 for all) |
| compid_target | The function will be called only if the commands targets the component compid_target of this system (0 for all) |
| function | Pointer to the function to be executed |
| module_struct | Pointer to module data structure to be given as argument to the function |


| bool Mavlink_message_handler::add_msg_callback | ( | uint8_t | message_id, |
| uint8_t | sysid_filter, | ||
| mav_component_t | compid_filter, | ||
| typename msg_function< T >::type_t | function, | ||
| T * | module_struct | ||
| ) |
Registers a new callback for a message.
You should call mavlink_message_handler_sort_callback function after having added all callbacks, as it is used by mavlink_message_handler_receive to speed up matching
| message_id | The function will be called only for messages with ID message_id |
| sysid_filter | The function will be called only for messages coming from MAVs with ID sysid_filter (0 for all) |
| compid_filter | The function will be called only for messages coming from component compid_filter (0 for all) |
| function | Pointer to the function to be executed |
| module_struct | Pointer to module data structure to be given as argument to the function |


| virtual cmd_callback_t* Mavlink_message_handler::cmd_callback_list | ( | void | ) | [protected, pure virtual] |
Get list of command callbacks.
To be overriden by child class
Implemented in Mavlink_message_handler_T< N, P >, and Mavlink_message_handler_T< N_MSG_CB, N_CMD_CB >.

| virtual uint32_t Mavlink_message_handler::cmd_callback_max_count | ( | void | ) | [protected, pure virtual] |
Get maximum number of command callbacks.
To be overriden by child class
Implemented in Mavlink_message_handler_T< N, P >, and Mavlink_message_handler_T< N_MSG_CB, N_CMD_CB >.

| void Mavlink_message_handler::cmd_default_dbg | ( | mavlink_command_long_t * | cmd | ) | [static] |
Dummy command callback for debug purpose.
Prints the fields of the incoming command to the debug console
| cmd | Pointer to incoming command |

| Mavlink_message_handler::conf_t Mavlink_message_handler::default_config | ( | void | ) | [inline, static] |
Default configuration.
| virtual msg_callback_t* Mavlink_message_handler::msg_callback_list | ( | void | ) | [protected, pure virtual] |
Get list of message callbacks.
To be overriden by child class
Implemented in Mavlink_message_handler_T< N, P >, and Mavlink_message_handler_T< N_MSG_CB, N_CMD_CB >.

| virtual uint32_t Mavlink_message_handler::msg_callback_max_count | ( | void | ) | [protected, pure virtual] |
Get maximum number of message callbacks.
To be overriden by child class
Implemented in Mavlink_message_handler_T< N, P >, and Mavlink_message_handler_T< N_MSG_CB, N_CMD_CB >.

| void Mavlink_message_handler::msg_default_dbg | ( | mavlink_message_t * | msg | ) | [static] |
Dummy message callback for debug purpose.
Prints the fields of the incoming message to the debug console
| msg | Pointer to incoming message |

Main update function, handles the incoming message according to the registered message and command callbacks.
| rec | Pointer to the MAVLink receive message structure |


1.7.6.1