mavsdk::MavlinkPassthrough Class Reference
#include: mavlink_passthrough.h
The MavlinkPassthrough class provides direct MAVLink access.
"With great power comes great responsibility." - This plugin allows you to send and receive MAVLink messages. There is no checking or safe-guards, you're on your own, and you have been warned.
This plugin is not included in the build by default. To add it
make ENABLE_MAVLINK_PASSTHROUGH=1
is required.
Public Types
Type | Description |
---|---|
enum Result | Possible results returned for requests. |
Public Member Functions
Type | Name | Description |
---|---|---|
MavlinkPassthrough (System & system) | Constructor. Creates the plugin for a specific System. | |
~MavlinkPassthrough () | Destructor (internal use only). | |
MavlinkPassthrough (const MavlinkPassthrough &)=delete | Copy Constructor (object is not copyable). | |
Result | send_message (mavlink_message_t & message) | Send message. |
void | subscribe_message_async (uint16_t message_id, std::function< void(const mavlink_message_t &)> callback) | Subscribe to messages using message ID. |
uint8_t | get_our_sysid () const | Get our own system ID. |
uint8_t | get_our_compid () const | Get our own component ID. |
uint8_t | get_target_sysid () const | Get system ID of target. |
uint8_t | get_target_compid () const | Get target component ID. |
void | intercept_incoming_messages_async (std::function< bool(mavlink_message_t &)> callback) | Intercept incoming messages. |
void | intercept_outgoing_messages_async (std::function< bool(mavlink_message_t &)> callback) | Intercept outgoing messages. |
const MavlinkPassthrough & | operator= (const MavlinkPassthrough &)=delete | Equality operator (object is not copyable). |
Constructor & Destructor Documentation
MavlinkPassthrough()
mavsdk::MavlinkPassthrough::MavlinkPassthrough(System &system)
Constructor. Creates the plugin for a specific System.
The plugin is typically created as shown below:
auto mavlink_passthrough = std::make_shared<MavlinkPassthrough>(system);
Parameters
- System& system - The specific system associated with this plugin.
~MavlinkPassthrough()
mavsdk::MavlinkPassthrough::~MavlinkPassthrough()
Destructor (internal use only).
MavlinkPassthrough()
mavsdk::MavlinkPassthrough::MavlinkPassthrough(const MavlinkPassthrough &)=delete
Copy Constructor (object is not copyable).
Parameters
- const MavlinkPassthrough& -
Member Enumeration Documentation
enum Result
Possible results returned for requests.
Value | Description |
---|---|
Unknown |
Unknown error. |
Success |
Success. |
ConnectionError |
Connection error. |
Member Function Documentation
send_message()
Result mavsdk::MavlinkPassthrough::send_message(mavlink_message_t &message)
Send message.
Parameters
- mavlink_message_t& message -
Returns
Result - result of the request.
subscribe_message_async()
void mavsdk::MavlinkPassthrough::subscribe_message_async(uint16_t message_id, std::function< void(const mavlink_message_t &)> callback)
Subscribe to messages using message ID.
This means that all future messages being received will trigger the callback to be called. To stop the subscription, call this method with nullptr
as the argument.
Parameters
- uint16_t message_id - The MAVLink message ID.
- std::function< void(const mavlink_message_t &)> callback - Callback to be called for message subscription.
get_our_sysid()
uint8_t mavsdk::MavlinkPassthrough::get_our_sysid() const
Get our own system ID.
Returns
uint8_t - our own system ID.
get_our_compid()
uint8_t mavsdk::MavlinkPassthrough::get_our_compid() const
Get our own component ID.
Returns
uint8_t - our own component ID.
get_target_sysid()
uint8_t mavsdk::MavlinkPassthrough::get_target_sysid() const
Get system ID of target.
Returns
uint8_t - system ID of target.
get_target_compid()
uint8_t mavsdk::MavlinkPassthrough::get_target_compid() const
Get target component ID.
This defaults to the component ID of the autopilot (1) if available and otherwise to all components (0).
Returns
uint8_t - component ID of target.
intercept_incoming_messages_async()
void mavsdk::MavlinkPassthrough::intercept_incoming_messages_async(std::function< bool(mavlink_message_t &)> callback)
Intercept incoming messages.
This is a hook which allows to change or drop MAVLink messages as they are received before they get forwarded to the core and the other plugins.
This functioniality is provided primarily for testing in order to simulate packet drops or actors not adhering to the MAVLink protocols.
Parameters
- std::function< bool(mavlink_message_t &)> callback - Callback to be called for each incoming message. To drop a message, return 'false' from the callback.
intercept_outgoing_messages_async()
void mavsdk::MavlinkPassthrough::intercept_outgoing_messages_async(std::function< bool(mavlink_message_t &)> callback)
Intercept outgoing messages.
This is a hook which allows to change or drop MAVLink messages before they are sent.
This functioniality is provided primarily for testing in order to simulate packet drops or actors not adhering to the MAVLink protocols.
Parameters
- std::function< bool(mavlink_message_t &)> callback - Callback to be called for each outgoing message. To drop a message, return 'false' from the callback.
operator=()
const MavlinkPassthrough& mavsdk::MavlinkPassthrough::operator=(const MavlinkPassthrough &)=delete
Equality operator (object is not copyable).
Parameters
- const MavlinkPassthrough& -
Returns
const MavlinkPassthrough & -