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.

Data Structures

struct CommandInt

struct CommandLong

Public Types

Type Description
enum Result Possible results returned for requests.
std::function< void(const mavlink_message_t &)> MessageCallback Callback type for message subscriptions.
Handle< const mavlink_message_t & > MessageHandle Handle type for subscribe_message_async.

Public Member Functions

Type Name Description
  MavlinkPassthrough (System & system) Constructor. Creates the plugin for a specific System.
  MavlinkPassthrough (std::shared_ptr< 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).
DEPRECATED Result send_message (mavlink_message_t & message) Send message (deprecated).
Result queue_message (std::function< mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun) Send message by queueing it.
Result send_command_long (const CommandLong & command) Send a MAVLink command_long.
Result send_command_int (const CommandInt & command) Send a MAVLink command_long.
mavlink_message_t make_command_ack_message (const uint8_t target_sysid, const uint8_t target_compid, const uint16_t command, MAV_RESULT result) Create a command_ack.
std::pair< Result, int32_t > get_param_int (const std::string & name, std::optional< uint8_t > maybe_component_id, bool extended) Request param (int).
std::pair< Result, float > get_param_float (const std::string & name, std::optional< uint8_t > maybe_component_id, bool extended) Request param (float).
MessageHandle subscribe_message (uint16_t message_id, const MessageCallback & callback) Subscribe to messages using message ID.
void unsubscribe_message (uint16_t message_id, MessageHandle handle) Unsubscribe from subscribe_message.
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.
const MavlinkPassthrough & operator= (const MavlinkPassthrough &)=delete Equality operator (object is not copyable).

Constructor & Destructor Documentation

mavsdk::MavlinkPassthrough::MavlinkPassthrough(System &system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto mavlink_passthrough = MavlinkPassthrough(system);

Parameters

  • System& system - The specific system associated with this plugin.
mavsdk::MavlinkPassthrough::MavlinkPassthrough(std::shared_ptr< System > system)

Constructor. Creates the plugin for a specific System.

The plugin is typically created as shown below:

auto mavlink_passthrough = MavlinkPassthrough(system);

Parameters

  • std::shared_ptr< System > system - The specific system associated with this plugin.
mavsdk::MavlinkPassthrough::~MavlinkPassthrough()

Destructor (internal use only).

mavsdk::MavlinkPassthrough::MavlinkPassthrough(const MavlinkPassthrough &)=delete

Copy Constructor (object is not copyable).

Parameters

Member Typdef Documentation

using mavsdk::MavlinkPassthrough::MessageCallback =  std::function<void(const mavlink_message_t&)>

Callback type for message subscriptions.

using mavsdk::MavlinkPassthrough::MessageHandle =  Handle<const mavlink_message_t&>

Handle type for subscribe_message_async.

Member Enumeration Documentation

Possible results returned for requests.

Value Description
Unknown Unknown error.
Success Success.
ConnectionError Connection error.
CommandNoSystem System not available.
CommandBusy System is busy.
CommandDenied Command has been denied.
CommandUnsupported Command is not supported.
CommandTimeout A timeout happened.
CommandTemporarilyRejected Command has been rejected for now.
CommandFailed Command has failed.
ParamWrongType Wrong type for requested param.
ParamNameTooLong Param name too long.
ParamValueTooLong Param value too long.
ParamNotFound Param not found.
ParamValueUnsupported Param value unsupported.

Member Function Documentation

DEPRECATED Result mavsdk::MavlinkPassthrough::send_message(mavlink_message_t &message)

Send message (deprecated).

This interface is deprecated. Instead the method queue_message() should be used.

Parameters

  • mavlink_message_t& message -

Returns

 DEPRECATED Result - result of the request.

Result mavsdk::MavlinkPassthrough::queue_message(std::function< mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun)

Send message by queueing it.

This interface replaces the previous send_message method.

The interface changed in order to prevent accessing the internal MAVLink status from different threads and to make sure the seq numbers are not unique toMavsdk instances and server components.

Parameters

  • std::function< mavlink_message_t(MavlinkAddress mavlink_address, uint8_t channel)> fun - Function which is (immediately) executed to send a message. It is passed the mavlink_address and channel, both data required to send a message using mavlink_message_xx_pack_chan().

Returns

Result - result of request

Result mavsdk::MavlinkPassthrough::send_command_long(const CommandLong &command)

Send a MAVLink command_long.

Parameters

Returns

Result - result of the request.

Result mavsdk::MavlinkPassthrough::send_command_int(const CommandInt &command)

Send a MAVLink command_long.

Parameters

Returns

Result - result of the request.

mavlink_message_t mavsdk::MavlinkPassthrough::make_command_ack_message(const uint8_t target_sysid, const uint8_t target_compid, const uint16_t command, MAV_RESULT result)

Create a command_ack.

Parameters

  • const uint8_t target_sysid - Target system ID where to send command_ack to.
  • const uint8_t target_compid - Target component ID where to send command_ack to.
  • const uint16_t command - Command to respond to.
  • MAV_RESULT result - Result of command.

Returns

 mavlink_message_t - message to send.

std::pair<Result, int32_t> mavsdk::MavlinkPassthrough::get_param_int(const std::string &name, std::optional< uint8_t > maybe_component_id, bool extended)

Request param (int).

Parameters

  • const std::string& name -
  • std::optional< uint8_t > maybe_component_id -
  • bool extended -

Returns

 std::pair< Result, int32_t > -

std::pair<Result, float> mavsdk::MavlinkPassthrough::get_param_float(const std::string &name, std::optional< uint8_t > maybe_component_id, bool extended)

Request param (float).

Parameters

  • const std::string& name -
  • std::optional< uint8_t > maybe_component_id -
  • bool extended -

Returns

 std::pair< Result, float > -

MessageHandle mavsdk::MavlinkPassthrough::subscribe_message(uint16_t message_id, const MessageCallback &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.
  • const MessageCallback& callback - Callback to be called for message subscription.

Returns

MessageHandle -

void mavsdk::MavlinkPassthrough::unsubscribe_message(uint16_t message_id, MessageHandle handle)

Unsubscribe from subscribe_message.

Parameters

  • uint16_t message_id - The MAVLink message ID.
  • MessageHandle handle - The handle returned from subscribe_message.
uint8_t mavsdk::MavlinkPassthrough::get_our_sysid() const

Get our own system ID.

Returns

 uint8_t - our own system ID.

uint8_t mavsdk::MavlinkPassthrough::get_our_compid() const

Get our own component ID.

Returns

 uint8_t - our own component ID.

uint8_t mavsdk::MavlinkPassthrough::get_target_sysid() const

Get system ID of target.

Returns

 uint8_t - system ID of target.

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.

const MavlinkPassthrough& mavsdk::MavlinkPassthrough::operator=(const MavlinkPassthrough &)=delete

Equality operator (object is not copyable).

Parameters

Returns

 const MavlinkPassthrough & -

© MAVSDK Development Team 2017-2023. License: CC BY 4.0            Updated: 2023-12-27 03:10:20

results matching ""

    No results matching ""