|
MAV'RIC
|
Main structure for the MAVLink stream module. More...
#include <mavlink_stream.hpp>
Classes | |
| struct | conf_t |
| Configuration structure for the module MAVLink stream. More... | |
| struct | msg_received_t |
| Mavlink structures for the receive message and its status. More... | |
Public Member Functions | |
| Mavlink_stream (Serial &serial, const conf_t &config=default_config()) | |
| Constructor. | |
| bool | send (mavlink_message_t *msg) const |
| Send Mavlink stream. | |
| bool | receive (msg_received_t *rec) |
| Mavlink parsing of message; the message is not available in this module afterwards. | |
| void | flush () |
| Flushing MAVLink stream. | |
| uint32_t | sysid () const |
| Return sysid of this stream. | |
| uint32_t | compid () const |
| Return sysid of this stream. | |
Static Public Member Functions | |
| static conf_t | default_config (void) |
| Default config of MAVLink stream. | |
Public Attributes | |
| uint32_t | sysid_ |
| System ID. | |
Main structure for the MAVLink stream module.
| uint32_t Mavlink_stream::compid | ( | ) | const [inline] |
Return sysid of this stream.

| bool Mavlink_stream::receive | ( | Mavlink_stream::msg_received_t * | rec | ) |
Mavlink parsing of message; the message is not available in this module afterwards.
| rec | Address where to store the received message |


| bool Mavlink_stream::send | ( | mavlink_message_t * | msg | ) | const |
Send Mavlink stream.
| msg | msg to stream |


| uint32_t Mavlink_stream::sysid | ( | ) | const [inline] |
Return sysid of this stream.

1.7.6.1