Firmware
Classes | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Protected Attributes | List of all members
Mavlink Class Reference
Inheritance diagram for Mavlink:
ModuleParams ListNode< ModuleParams *>

Classes

struct  ping_statistics_s
 

Public Types

enum  MAVLINK_MODE {
  MAVLINK_MODE_NORMAL = 0, MAVLINK_MODE_CUSTOM, MAVLINK_MODE_ONBOARD, MAVLINK_MODE_OSD,
  MAVLINK_MODE_MAGIC, MAVLINK_MODE_CONFIG, MAVLINK_MODE_IRIDIUM, MAVLINK_MODE_MINIMAL,
  MAVLINK_MODE_EXTVISION, MAVLINK_MODE_COUNT
}
 
enum  BROADCAST_MODE { BROADCAST_MODE_OFF = 0, BROADCAST_MODE_ON, BROADCAST_MODE_MULTICAST }
 
enum  FLOW_CONTROL_MODE { FLOW_CONTROL_OFF = 0, FLOW_CONTROL_AUTO, FLOW_CONTROL_ON }
 

Public Member Functions

 Mavlink ()
 Constructor.
 
 ~Mavlink ()
 Destructor, also kills the mavlinks task.
 
void display_status ()
 Display the mavlink status.
 
void display_status_streams ()
 Display the status of all enabled streams.
 
mavlink_message_t * get_buffer ()
 
mavlink_status_t * get_status ()
 
void set_proto_version (unsigned version)
 Set the MAVLink version. More...
 
int get_uart_fd () const
 
int get_system_id () const
 Get the MAVLink system id. More...
 
int get_component_id () const
 Get the MAVLink component id. More...
 
enum MAVLINK_MODE get_mode ()
 
bool get_hil_enabled ()
 
bool get_use_hil_gps ()
 
bool get_forward_externalsp ()
 
bool get_flow_control_enabled ()
 
bool get_forwarding_on ()
 
bool is_connected ()
 
bool broadcast_enabled ()
 
unsigned get_free_tx_buf ()
 Get the free space in the transmit buffer. More...
 
int set_hil_enabled (bool hil_enabled)
 Enable / disable Hardware in the Loop simulation mode. More...
 
void set_manual_input_mode_generation (bool generation_enabled)
 Set manual input generation mode. More...
 
void set_protocol (Protocol p)
 Set communication protocol for this mavlink instance.
 
bool get_manual_input_mode_generation ()
 Get the manual input generation mode. More...
 
void begin_send ()
 This is the beginning of a MAVLINK_START_UART_SEND/MAVLINK_END_UART_SEND transaction.
 
void send_bytes (const uint8_t *buf, unsigned packet_len)
 Send bytes out on the link. More...
 
int send_packet ()
 Flush the transmit buffer and send one MAVLink packet. More...
 
void resend_message (mavlink_message_t *msg)
 Resend message as is, don't change sequence number and CRC.
 
void handle_message (const mavlink_message_t *msg)
 
MavlinkOrbSubscriptionadd_orb_subscription (const orb_id_t topic, int instance=0, bool disable_sharing=false)
 Add a mavlink orb topic subscription while ensuring that only a single object exists for a given topic id and instance. More...
 
int get_instance_id () const
 
int enable_flow_control (enum FLOW_CONTROL_MODE enabled)
 Enable / disable hardware flow control. More...
 
mavlink_channel_t get_channel () const
 
void configure_stream_threadsafe (const char *stream_name, float rate=-1.0f)
 
orb_advert_tget_mavlink_log_pub ()
 
void send_statustext_info (const char *string)
 Send a status text with loglevel INFO. More...
 
void send_statustext_critical (const char *string)
 Send a status text with loglevel CRITICAL. More...
 
void send_statustext_emergency (const char *string)
 Send a status text with loglevel EMERGENCY. More...
 
void send_statustext (unsigned char severity, const char *string)
 Send a status text with loglevel, the difference from mavlink_log_xxx() is that message sent only on this mavlink connection. More...
 
void send_autopilot_capabilites ()
 Send the capabilities of this autopilot in terms of the MAVLink spec.
 
void send_protocol_version ()
 Send the protocol version of MAVLink.
 
List< MavlinkStream * > & get_streams ()
 
float get_rate_mult () const
 
float get_baudrate ()
 
void set_has_received_messages (bool received_messages)
 
bool get_has_received_messages ()
 
void set_wait_to_transmit (bool wait)
 
bool get_wait_to_transmit ()
 
bool should_transmit ()
 
bool message_buffer_write (const void *ptr, int size)
 
void lockMessageBufferMutex (void)
 
void unlockMessageBufferMutex (void)
 
void count_txbytes (unsigned n)
 Count transmitted bytes.
 
void count_txerrbytes (unsigned n)
 Count bytes not transmitted because of errors.
 
void count_rxbytes (unsigned n)
 Count received bytes.
 
telemetry_status_s & get_telemetry_status ()
 Get the receive status of this MAVLink link.
 
void set_telemetry_status_type (uint8_t type)
 
void update_radio_status (const radio_status_s &radio_status)
 
ringbuffer::RingBuffer * get_logbuffer ()
 
unsigned get_system_type ()
 
Protocol get_protocol ()
 
unsigned short get_network_port ()
 
unsigned short get_remote_port ()
 
int get_socket_fd ()
 
bool get_client_source_initialized ()
 
uint64_t get_start_time ()
 
bool is_usb_uart ()
 
int get_data_rate ()
 
void set_data_rate (int rate)
 
unsigned get_main_loop_delay () const
 
MavlinkShellget_shell ()
 get the Mavlink shell. More...
 
void close_shell ()
 close the Mavlink shell if it is open
 
MavlinkULogget_ulog_streaming ()
 get ulog streaming if active, nullptr otherwise
 
void try_start_ulog_streaming (uint8_t target_system, uint8_t target_component)
 
void request_stop_ulog_streaming ()
 
void set_uorb_main_fd (int fd, unsigned int interval)
 
bool ftp_enabled () const
 
bool hash_check_enabled () const
 
bool forward_heartbeats_enabled () const
 
bool odometry_loopback_enabled () const
 
struct ping_statistics_sget_ping_statistics ()
 Get the ping statistics of this MAVLink link.
 
- Public Member Functions inherited from ModuleParams
 ModuleParams (ModuleParams *parent)
 
void setParent (ModuleParams *parent)
 Sets the parent module. More...
 
 ModuleParams (const ModuleParams &)=delete
 
ModuleParamsoperator= (const ModuleParams &)=delete
 
 ModuleParams (ModuleParams &&)=delete
 
ModuleParamsoperator= (ModuleParams &&)=delete
 
- Public Member Functions inherited from ListNode< ModuleParams *>
void setSibling (ModuleParams * sibling)
 
const ModuleParamsgetSibling () const
 

Static Public Member Functions

static int start (int argc, char *argv[])
 Start the mavlink task. More...
 
static int stream_command (int argc, char *argv[])
 
static int instance_count ()
 
static Mavlinknew_instance ()
 
static Mavlinkget_instance (int instance)
 
static Mavlinkget_instance_for_device (const char *device_name)
 
static Mavlinkget_instance_for_network_port (unsigned long port)
 
static int destroy_all_instances ()
 
static int get_status_all_instances (bool show_streams_status)
 
static bool instance_exists (const char *device_name, Mavlink *self)
 
static void forward_message (const mavlink_message_t *msg, Mavlink *self)
 
static int get_uart_fd (unsigned index)
 
static const char * mavlink_mode_str (enum MAVLINK_MODE mode)
 
static void set_boot_complete ()
 Set the boot complete flag on all instances. More...
 
static int start_helper (int argc, char *argv[])
 
static bool boot_complete ()
 

Public Attributes

const char * _device_name {DEFAULT_DEVICE_NAME}
 
bool _task_should_exit {false}
 Mavlink task should exit iff true. More...
 

Protected Attributes

Mavlinknext {nullptr}
 
- Protected Attributes inherited from ListNode< ModuleParams *>
ModuleParams_sibling
 

Additional Inherited Members

- Protected Member Functions inherited from ModuleParams
virtual void updateParams ()
 Call this method whenever the module gets a parameter change notification. More...
 
virtual void updateParamsImpl ()
 The implementation for this is generated with the macro DEFINE_PARAMETERS()
 

Member Function Documentation

§ add_orb_subscription()

MavlinkOrbSubscription * Mavlink::add_orb_subscription ( const orb_id_t  topic,
int  instance = 0,
bool  disable_sharing = false 
)

Add a mavlink orb topic subscription while ensuring that only a single object exists for a given topic id and instance.

Parameters
topicorb topic id
instancetopic instance
disable_sharingif true, force creating a new instance

§ enable_flow_control()

int Mavlink::enable_flow_control ( enum FLOW_CONTROL_MODE  enabled)

Enable / disable hardware flow control.

Parameters
enabledTrue if hardware flow control should be enabled

§ get_component_id()

int Mavlink::get_component_id ( ) const
inline

Get the MAVLink component id.

Returns
The component ID of this vehicle

§ get_free_tx_buf()

unsigned Mavlink::get_free_tx_buf ( )

Get the free space in the transmit buffer.

Returns
free space in the UART TX buffer

§ get_manual_input_mode_generation()

bool Mavlink::get_manual_input_mode_generation ( )
inline

Get the manual input generation mode.

Returns
true if manual inputs should generate RC data

§ get_shell()

MavlinkShell * Mavlink::get_shell ( )

get the Mavlink shell.

Create a new one if there isn't one. It is always created via MavlinkReceiver thread. Returns nullptr if shell cannot be created

§ get_system_id()

int Mavlink::get_system_id ( ) const
inline

Get the MAVLink system id.

Returns
The system ID of this vehicle

§ send_bytes()

void Mavlink::send_bytes ( const uint8_t *  buf,
unsigned  packet_len 
)

Send bytes out on the link.

On a network port these might actually get buffered to form a packet.

§ send_packet()

int Mavlink::send_packet ( )

Flush the transmit buffer and send one MAVLink packet.

Returns
the number of bytes sent or -1 in case of error

§ send_statustext()

void Mavlink::send_statustext ( unsigned char  severity,
const char *  string 
)

Send a status text with loglevel, the difference from mavlink_log_xxx() is that message sent only on this mavlink connection.

Useful for reporting communication specific, not system-wide info only to client interested in it. Message will be not sent immediately but queued in buffer as for mavlink_log_xxx().

Parameters
stringthe message to send (will be capped by mavlink max string length)
severitythe log level

§ send_statustext_critical()

void Mavlink::send_statustext_critical ( const char *  string)

Send a status text with loglevel CRITICAL.

Parameters
stringthe message to send (will be capped by mavlink max string length)

§ send_statustext_emergency()

void Mavlink::send_statustext_emergency ( const char *  string)

Send a status text with loglevel EMERGENCY.

Parameters
stringthe message to send (will be capped by mavlink max string length)

§ send_statustext_info()

void Mavlink::send_statustext_info ( const char *  string)

Send a status text with loglevel INFO.

Parameters
stringthe message to send (will be capped by mavlink max string length)

§ set_boot_complete()

void Mavlink::set_boot_complete ( )
static

Set the boot complete flag on all instances.

Setting the flag unblocks parameter transmissions, which are gated beforehand to ensure that the system is fully initialized.

§ set_hil_enabled()

int Mavlink::set_hil_enabled ( bool  hil_enabled)

Enable / disable Hardware in the Loop simulation mode.

Parameters
hil_enabledThe new HIL enable/disable state.
Returns
OK if the HIL state changed, ERROR if the requested change could not be made or was redundant.

§ set_manual_input_mode_generation()

void Mavlink::set_manual_input_mode_generation ( bool  generation_enabled)
inline

Set manual input generation mode.

Set to true to generate RC_INPUT messages on the system bus from MAVLink messages.

Parameters
generation_enabledIf set to true, generate RC_INPUT messages

§ set_proto_version()

void Mavlink::set_proto_version ( unsigned  version)

Set the MAVLink version.

Currently supporting v1 and v2

Parameters
versionMAVLink version

§ start()

int Mavlink::start ( int  argc,
char *  argv[] 
)
static

Start the mavlink task.

Returns
OK on success.

Member Data Documentation

§ _task_should_exit

bool Mavlink::_task_should_exit {false}

Mavlink task should exit iff true.


The documentation for this class was generated from the following files: