PX4 Firmware
PX4 Autopilot Software http://px4.io
Mavlink Class Reference

#include <mavlink_main.h>

Inheritance diagram for Mavlink:
Collaboration diagram for Mavlink:

Classes

struct  mavlink_message_buffer
 
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_EXTVISIONMIN, 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. More...
 
 ~Mavlink ()
 Destructor, also kills the mavlinks task. More...
 
void display_status ()
 Display the mavlink status. More...
 
void display_status_streams ()
 Display the status of all enabled streams. More...
 
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 ()
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
void send_protocol_version ()
 Send the protocol version of MAVLink. More...
 
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. More...
 
void count_txerrbytes (unsigned n)
 Count bytes not transmitted because of errors. More...
 
void count_rxbytes (unsigned n)
 Count received bytes. More...
 
telemetry_status_sget_telemetry_status ()
 Get the receive status of this MAVLink link. More...
 
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 () const
 
int get_socket_fd ()
 
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 More...
 
MavlinkULogget_ulog_streaming ()
 get ulog streaming if active, nullptr otherwise More...
 
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. More...
 

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 int destroy_all_instances ()
 
static int get_status_all_instances (bool show_streams_status)
 
static bool serial_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 ()
 
static hrt_abstimeget_first_start_time ()
 

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}
 

Private Member Functions

 DEFINE_PARAMETERS ((ParamInt< px4::params::MAV_SYS_ID >) _param_mav_sys_id,(ParamInt< px4::params::MAV_COMP_ID >) _param_mav_comp_id,(ParamInt< px4::params::MAV_PROTO_VER >) _param_mav_proto_ver,(ParamInt< px4::params::MAV_RADIO_ID >) _param_mav_radio_id,(ParamInt< px4::params::MAV_TYPE >) _param_mav_type,(ParamBool< px4::params::MAV_USEHILGPS >) _param_mav_usehilgps,(ParamBool< px4::params::MAV_FWDEXTSP >) _param_mav_fwdextsp,(ParamBool< px4::params::MAV_HASH_CHK_EN >) _param_mav_hash_chk_en,(ParamBool< px4::params::MAV_HB_FORW_EN >) _param_mav_hb_forw_en,(ParamBool< px4::params::MAV_ODOM_LP >) _param_mav_odom_lp,(ParamInt< px4::params::SYS_HITL >) _param_sys_hitl) perf_counter_t _loop_perf
 
void mavlink_update_parameters ()
 
int mavlink_open_uart (const int baudrate=DEFAULT_BAUD_RATE, const char *uart_name=DEFAULT_DEVICE_NAME, const bool force_flow_control=false)
 
int configure_stream (const char *stream_name, const float rate=-1.0f)
 Configure a single stream. More...
 
int configure_streams_to_default (const char *configure_single_stream=nullptr)
 Configure default streams according to _mode for either all streams or only a single stream. More...
 
int message_buffer_init (int size)
 
void message_buffer_destroy ()
 
int message_buffer_count ()
 
int message_buffer_is_empty () const
 
int message_buffer_get_ptr (void **ptr, bool *is_part)
 
void message_buffer_mark_read (int n)
 
void pass_message (const mavlink_message_t *msg)
 
void publish_telemetry_status ()
 
void check_requested_subscriptions ()
 
void check_radio_config ()
 Check the configuration of a connected radio. More...
 
void update_rate_mult ()
 Update rate mult so total bitrate will be equal to _datarate. More...
 
void set_channel ()
 
void set_instance_id ()
 
int task_main (int argc, char *argv[])
 Main mavlink task. More...
 
 Mavlink (const Mavlink &)=delete
 
Mavlink operator= (const Mavlink &)=delete
 

Private Attributes

int _instance_id {0}
 
bool _transmitting_enabled {true}
 
bool _transmitting_enabled_commanded {false}
 
bool _first_heartbeat_sent {false}
 
orb_advert_t _mavlink_log_pub {nullptr}
 
uORB::PublicationQueued< telemetry_status_s_telem_status_pub {ORB_ID(telemetry_status)}
 
bool _task_running {true}
 
mavlink_message_t _mavlink_buffer {}
 
mavlink_status_t _mavlink_status {}
 
bool _hil_enabled {false}
 Hardware In the Loop mode. More...
 
bool _generate_rc {false}
 Generate RC messages from manual input MAVLink messages. More...
 
bool _is_usb_uart {false}
 Port is USB. More...
 
bool _wait_to_transmit {false}
 Wait to transmit until received messages. More...
 
bool _received_messages {false}
 Whether we've received valid mavlink messages. More...
 
unsigned _main_loop_delay {1000}
 mainloop delay, depends on data rate More...
 
List< MavlinkOrbSubscription * > _subscriptions
 
List< MavlinkStream * > _streams
 
MavlinkShell_mavlink_shell {nullptr}
 
MavlinkULog_mavlink_ulog {nullptr}
 
volatile bool _mavlink_ulog_stop_requested {false}
 
MAVLINK_MODE _mode {MAVLINK_MODE_NORMAL}
 
mavlink_channel_t _channel {MAVLINK_COMM_0}
 
ringbuffer::RingBuffer _logbuffer {5, sizeof(mavlink_log_s)}
 
pthread_t _receive_thread {}
 
bool _forwarding_on {false}
 
bool _ftp_on {false}
 
int _uart_fd {-1}
 
int _baudrate {57600}
 
int _datarate {1000}
 data rate for normal streams (attitude, position, etc.) More...
 
float _rate_mult {1.0f}
 
bool _radio_status_available {false}
 
bool _radio_status_critical {false}
 
float _radio_status_mult {1.0f}
 
unsigned int _mavlink_param_queue_index {0}
 If the queue index is not at 0, the queue sending logic will send parameters from the current index to len - 1, the end of the param list. More...
 
bool _mavlink_link_termination_allowed {false}
 
char * _subscribe_to_stream {nullptr}
 
float _subscribe_to_stream_rate {0.0f}
 rate of stream to subscribe to (0=disable, -1=unlimited, -2=default) More...
 
bool _udp_initialised {false}
 
FLOW_CONTROL_MODE _flow_control_mode {Mavlink::FLOW_CONTROL_OFF}
 
uint64_t _last_write_success_time {0}
 
uint64_t _last_write_try_time {0}
 
uint64_t _mavlink_start_time {0}
 
int32_t _protocol_version_switch {-1}
 
int32_t _protocol_version {0}
 
unsigned _bytes_tx {0}
 
unsigned _bytes_txerr {0}
 
unsigned _bytes_rx {0}
 
uint64_t _bytes_timestamp {0}
 
const char * _interface_name {nullptr}
 
int _socket_fd {-1}
 
Protocol _protocol {Protocol::SERIAL}
 
radio_status_s _rstatus {}
 
telemetry_status_s _tstatus {}
 
ping_statistics_s _ping_stats {}
 
mavlink_message_buffer _message_buffer {}
 
pthread_mutex_t _message_buffer_mutex {}
 
pthread_mutex_t _send_mutex {}
 
perf_counter_t _loop_interval_perf {perf_alloc(PC_INTERVAL, "mavlink_int")}
 loop performance counter More...
 

Static Private Attributes

static bool _boot_complete = false
 
static constexpr int MAVLINK_MAX_INSTANCES {4}
 
static constexpr int MAVLINK_MIN_INTERVAL {1500}
 
static constexpr int MAVLINK_MAX_INTERVAL {10000}
 
static constexpr float MAVLINK_MIN_MULTIPLIER {0.0005f}
 
static constexpr unsigned RADIO_BUFFER_CRITICAL_LOW_PERCENTAGE = 25
 
static constexpr unsigned RADIO_BUFFER_LOW_PERCENTAGE = 35
 
static constexpr unsigned RADIO_BUFFER_HALF_PERCENTAGE = 50
 
static hrt_abstime _first_start_time = {0}
 

Detailed Description

Definition at line 105 of file mavlink_main.h.

Member Enumeration Documentation

◆ BROADCAST_MODE

Enumerator
BROADCAST_MODE_OFF 
BROADCAST_MODE_ON 
BROADCAST_MODE_MULTICAST 

Definition at line 202 of file mavlink_main.h.

◆ FLOW_CONTROL_MODE

Enumerator
FLOW_CONTROL_OFF 
FLOW_CONTROL_AUTO 
FLOW_CONTROL_ON 

Definition at line 208 of file mavlink_main.h.

◆ MAVLINK_MODE

Enumerator
MAVLINK_MODE_NORMAL 
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_EXTVISIONMIN 
MAVLINK_MODE_COUNT 

Definition at line 187 of file mavlink_main.h.

Constructor & Destructor Documentation

◆ Mavlink() [1/2]

Mavlink::Mavlink ( )

Constructor.

Definition at line 164 of file mavlink_main.cpp.

References _first_start_time, hrt_absolute_time(), mavlink_system, and mavlink_update_parameters().

Referenced by start_helper().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ ~Mavlink()

Mavlink::~Mavlink ( )

Destructor, also kills the mavlinks task.

Definition at line 188 of file mavlink_main.cpp.

References _loop_interval_perf, _task_running, _task_should_exit, and perf_free().

Here is the call graph for this function:

◆ Mavlink() [2/2]

Mavlink::Mavlink ( const Mavlink )
privatedelete

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

Definition at line 1258 of file mavlink_main.cpp.

References _subscriptions, List::add(), and ll40ls::instance.

Referenced by MavlinkStreamActuatorControlTarget< N >::MavlinkStreamActuatorControlTarget(), MavlinkStreamBatteryStatus::MavlinkStreamBatteryStatus(), MavlinkStreamHighLatency2::MavlinkStreamHighLatency2(), MavlinkStreamSysStatus::MavlinkStreamSysStatus(), send_autopilot_capabilites(), and task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ begin_send()

void Mavlink::begin_send ( )
inline

This is the beginning of a MAVLINK_START_UART_SEND/MAVLINK_END_UART_SEND transaction.

Definition at line 324 of file mavlink_main.h.

References tap_esc_common::send_packet().

Referenced by mavlink_start_uart_send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ boot_complete()

static bool Mavlink::boot_complete ( )
inlinestatic

Definition at line 483 of file mavlink_main.h.

Referenced by MavlinkReceiver::Run().

Here is the caller graph for this function:

◆ check_radio_config()

void Mavlink::check_radio_config ( )
private

Check the configuration of a connected radio.

This convenience function allows to re-configure a connected radio without removing it from the main system harness.

Definition at line 2614 of file mavlink_main.cpp.

References _tstatus, _uart_fd, and telemetry_status_s::type.

Referenced by task_main().

Here is the caller graph for this function:

◆ check_requested_subscriptions()

void Mavlink::check_requested_subscriptions ( )
private

Definition at line 2523 of file mavlink_main.cpp.

References _device_name, _subscribe_to_stream, _subscribe_to_stream_rate, configure_stream(), configure_streams_to_default(), f(), get_protocol(), and SERIAL.

Referenced by task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ close_shell()

void Mavlink::close_shell ( )

close the Mavlink shell if it is open

Definition at line 1500 of file mavlink_main.cpp.

References _mavlink_shell.

Referenced by MavlinkReceiver::handle_message_serial_control().

Here is the caller graph for this function:

◆ configure_stream()

int Mavlink::configure_stream ( const char *  stream_name,
const float  rate = -1.0f 
)
private

Configure a single stream.

Parameters
stream_name
ratestreaming rate in Hz, -1 = unlimited rate
Returns
0 on success, <0 on error

Definition at line 1279 of file mavlink_main.cpp.

References _streams, create_mavlink_stream(), f(), OK, and MavlinkStream::set_interval().

Referenced by check_requested_subscriptions(), configure_streams_to_default(), set_hil_enabled(), and task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ configure_stream_threadsafe()

void Mavlink::configure_stream_threadsafe ( const char *  stream_name,
float  rate = -1.0f 
)

Definition at line 1332 of file mavlink_main.cpp.

References _subscribe_to_stream, _subscribe_to_stream_rate, _task_should_exit, and MAIN_LOOP_DELAY.

Referenced by MavlinkReceiver::handle_message_command_both(), MavlinkReceiver::set_message_interval(), and stream_command().

Here is the caller graph for this function:

◆ configure_streams_to_default()

int Mavlink::configure_streams_to_default ( const char *  configure_single_stream = nullptr)
private

Configure default streams according to _mode for either all streams or only a single stream.

Parameters
configure_single_streamif nullptr, configure all streams, else only a single stream
Returns
0 on success, <0 on error

Definition at line 1591 of file mavlink_main.cpp.

References _mode, configure_stream(), f(), MAVLINK_MODE_CONFIG, MAVLINK_MODE_CUSTOM, MAVLINK_MODE_EXTVISION, MAVLINK_MODE_EXTVISIONMIN, MAVLINK_MODE_IRIDIUM, MAVLINK_MODE_MAGIC, MAVLINK_MODE_MINIMAL, MAVLINK_MODE_NORMAL, MAVLINK_MODE_ONBOARD, and MAVLINK_MODE_OSD.

Referenced by check_requested_subscriptions(), and task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ count_rxbytes()

void Mavlink::count_rxbytes ( unsigned  n)
inline

Count received bytes.

Definition at line 444 of file mavlink_main.h.

Referenced by MavlinkReceiver::Run().

Here is the caller graph for this function:

◆ count_txbytes()

void Mavlink::count_txbytes ( unsigned  n)
inline

Count transmitted bytes.

Definition at line 434 of file mavlink_main.h.

Referenced by send_bytes().

Here is the caller graph for this function:

◆ count_txerrbytes()

void Mavlink::count_txerrbytes ( unsigned  n)
inline

Count bytes not transmitted because of errors.

Definition at line 439 of file mavlink_main.h.

Referenced by send_bytes().

Here is the caller graph for this function:

◆ DEFINE_PARAMETERS()

Mavlink::DEFINE_PARAMETERS ( (ParamInt< px4::params::MAV_SYS_ID >)  _param_mav_sys_id,
(ParamInt< px4::params::MAV_COMP_ID >)  _param_mav_comp_id,
(ParamInt< px4::params::MAV_PROTO_VER >)  _param_mav_proto_ver,
(ParamInt< px4::params::MAV_RADIO_ID >)  _param_mav_radio_id,
(ParamInt< px4::params::MAV_TYPE >)  _param_mav_type,
(ParamBool< px4::params::MAV_USEHILGPS >)  _param_mav_usehilgps,
(ParamBool< px4::params::MAV_FWDEXTSP >)  _param_mav_fwdextsp,
(ParamBool< px4::params::MAV_HASH_CHK_EN >)  _param_mav_hash_chk_en,
(ParamBool< px4::params::MAV_HB_FORW_EN >)  _param_mav_hb_forw_en,
(ParamBool< px4::params::MAV_ODOM_LP >)  _param_mav_odom_lp,
(ParamInt< px4::params::SYS_HITL >)  _param_sys_hitl 
)
inlineprivate

Definition at line 663 of file mavlink_main.h.

References PC_ELAPSED, and perf_alloc.

◆ destroy_all_instances()

int Mavlink::destroy_all_instances ( )
static

Definition at line 357 of file mavlink_main.cpp.

References _mavlink_instances, _task_running, _task_should_exit, LL_DELETE, next, and OK.

Referenced by mavlink_main().

Here is the caller graph for this function:

◆ display_status()

◆ display_status_streams()

void Mavlink::display_status_streams ( )

Display the status of all enabled streams.

Definition at line 2838 of file mavlink_main.cpp.

References _rate_mult, and _streams.

Referenced by get_status_all_instances().

Here is the caller graph for this function:

◆ 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

Definition at line 688 of file mavlink_main.cpp.

References _flow_control_mode, _is_usb_uart, _uart_fd, FLOW_CONTROL_OFF, and OK.

Referenced by get_free_tx_buf(), and mavlink_open_uart().

Here is the caller graph for this function:

◆ forward_heartbeats_enabled()

bool Mavlink::forward_heartbeats_enabled ( ) const
inline

Definition at line 517 of file mavlink_main.h.

◆ forward_message()

void Mavlink::forward_message ( const mavlink_message_t *  msg,
Mavlink self 
)
static

Definition at line 446 of file mavlink_main.cpp.

References LL_FOREACH, and pass_message().

Referenced by handle_message().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ ftp_enabled()

bool Mavlink::ftp_enabled ( ) const
inline

Definition at line 514 of file mavlink_main.h.

Referenced by publish_telemetry_status(), and MavlinkReceiver::Run().

Here is the caller graph for this function:

◆ get_baudrate()

float Mavlink::get_baudrate ( )
inline

Definition at line 417 of file mavlink_main.h.

Referenced by MavlinkReceiver::Run().

Here is the caller graph for this function:

◆ get_buffer()

mavlink_message_t* Mavlink::get_buffer ( )
inline

Definition at line 146 of file mavlink_main.h.

Referenced by mavlink_get_channel_buffer().

Here is the caller graph for this function:

◆ get_channel()

mavlink_channel_t Mavlink::get_channel ( ) const
inline

Definition at line 365 of file mavlink_main.h.

References f().

Referenced by MavlinkFTP::_getServerChannel(), MavlinkLogHandler::_log_send_data(), MavlinkLogHandler::_log_send_listing(), MavlinkFTP::_process_request(), MavlinkFTP::_reply(), MavlinkReceiver::get_message_interval(), MavlinkParametersManager::handle_message(), MavlinkTimesync::handle_message(), MavlinkReceiver::handle_message_command_ack(), MavlinkReceiver::handle_message_heartbeat(), MavlinkReceiver::handle_message_ping(), MavlinkReceiver::handle_message_radio_status(), MavlinkReceiver::Run(), MavlinkStreamHighLatency2::send(), MavlinkStreamHeartbeat::send(), MavlinkStreamStatustext::send(), MavlinkStreamCommandLong::send(), MavlinkStreamSysStatus::send(), MavlinkStreamBatteryStatus::send(), MavlinkStreamHighresIMU::send(), MavlinkStreamScaledIMU::send(), MavlinkStreamScaledIMU2::send(), MavlinkStreamScaledIMU3::send(), MavlinkStreamAttitude::send(), MavlinkStreamAttitudeQuaternion::send(), MavlinkStreamVFRHUD::send(), MavlinkStreamGPSRawInt::send(), MavlinkStreamGPS2Raw::send(), MavlinkStreamSystemTime::send(), MavlinkStreamTimesync::send(), MavlinkStreamADSBVehicle::send(), MavlinkStreamUTMGlobalPosition::send(), MavlinkStreamCollision::send(), MavlinkStreamCameraTrigger::send(), MavlinkStreamCameraImageCaptured::send(), MavlinkStreamGlobalPositionInt::send(), MavlinkStreamOdometry::send(), MavlinkStreamLocalPositionNED::send(), MavlinkStreamEstimatorStatus::send(), MavlinkStreamAttPosMocap::send(), MavlinkStreamHomePosition::send(), MavlinkStreamServoOutputRaw< N >::send(), MavlinkStreamActuatorControlTarget< N >::send(), MavlinkStreamHILActuatorControls::send(), MavlinkStreamPositionTargetGlobalInt::send(), MavlinkStreamLocalPositionSetpoint::send(), MavlinkStreamAttitudeTarget::send(), MavlinkStreamRCChannels::send(), MavlinkStreamManualControl::send(), MavlinkStreamTrajectoryRepresentationWaypoints::send(), MavlinkStreamOpticalFlowRad::send(), MavlinkStreamNamedValueFloat::send(), MavlinkStreamDebug::send(), MavlinkStreamDebugVect::send(), MavlinkStreamDebugFloatArray::send(), MavlinkStreamNavControllerOutput::send(), MavlinkStreamCameraCapture::send(), MavlinkStreamDistanceSensor::send(), MavlinkStreamExtendedSysState::send(), MavlinkStreamAltitude::send(), MavlinkStreamWind::send(), MavlinkStreamMountOrientation::send(), MavlinkStreamGroundTruth::send(), MavlinkStreamPing::send(), MavlinkStreamOrbitStatus::send(), MavlinkStreamObstacleDistance::send(), send_autopilot_capabilites(), MavlinkReceiver::send_flight_information(), MavlinkMissionManager::send_mission_ack(), MavlinkMissionManager::send_mission_count(), MavlinkMissionManager::send_mission_current(), MavlinkMissionManager::send_mission_item(), MavlinkMissionManager::send_mission_item_reached(), MavlinkMissionManager::send_mission_request(), MavlinkParametersManager::send_one(), MavlinkParametersManager::send_param(), send_protocol_version(), MavlinkReceiver::send_storage_information(), MavlinkParametersManager::send_uavcan(), and task_main().

Here is the call graph for this function:

◆ get_component_id()

int Mavlink::get_component_id ( ) const
inline

Get the MAVLink component id.

Returns
The component ID of this vehicle

Definition at line 183 of file mavlink_main.h.

References mavlink_system.

Referenced by MavlinkFTP::_getServerComponentId().

Here is the caller graph for this function:

◆ get_data_rate()

int Mavlink::get_data_rate ( )
inline

Definition at line 487 of file mavlink_main.h.

Referenced by MavlinkReceiver::handle_message_command_both().

Here is the caller graph for this function:

◆ get_first_start_time()

static hrt_abstime& Mavlink::get_first_start_time ( )
inlinestatic

Definition at line 535 of file mavlink_main.h.

Referenced by MavlinkReceiver::Run().

Here is the caller graph for this function:

◆ get_flow_control_enabled()

bool Mavlink::get_flow_control_enabled ( )
inline

Definition at line 260 of file mavlink_main.h.

Referenced by publish_telemetry_status(), and update_rate_mult().

Here is the caller graph for this function:

◆ get_forward_externalsp()

bool Mavlink::get_forward_externalsp ( )
inline

Definition at line 258 of file mavlink_main.h.

Referenced by MavlinkReceiver::handle_message_set_attitude_target(), MavlinkReceiver::handle_message_set_position_target_global_int(), and MavlinkReceiver::handle_message_set_position_target_local_ned().

Here is the caller graph for this function:

◆ get_forwarding_on()

bool Mavlink::get_forwarding_on ( )
inline

Definition at line 262 of file mavlink_main.h.

Referenced by handle_message(), and publish_telemetry_status().

Here is the caller graph for this function:

◆ 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

Definition at line 747 of file mavlink_main.cpp.

References _flow_control_mode, _last_write_success_time, _last_write_try_time, _uart_fd, enable_flow_control(), FLOW_CONTROL_AUTO, FLOW_CONTROL_DISABLE_THRESHOLD, FLOW_CONTROL_OFF, get_protocol(), and hrt_elapsed_time().

Referenced by MavlinkFTP::send(), MavlinkParametersManager::send(), MavlinkLogHandler::send(), send_bytes(), MavlinkParametersManager::send_param(), MavlinkParametersManager::send_untransmitted(), and task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_has_received_messages()

bool Mavlink::get_has_received_messages ( )
inline

Definition at line 421 of file mavlink_main.h.

◆ get_hil_enabled()

bool Mavlink::get_hil_enabled ( )
inline

Definition at line 254 of file mavlink_main.h.

Referenced by MavlinkReceiver::handle_message().

Here is the caller graph for this function:

◆ get_instance()

Mavlink * Mavlink::get_instance ( int  instance)
static

Definition at line 314 of file mavlink_main.cpp.

References get_instance_id(), and LL_FOREACH.

Referenced by get_uart_fd(), mavlink_end_uart_send(), mavlink_get_channel_buffer(), mavlink_get_channel_status(), mavlink_send_uart_bytes(), and mavlink_start_uart_send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_instance_for_device()

Mavlink * Mavlink::get_instance_for_device ( const char *  device_name)
static

Definition at line 327 of file mavlink_main.cpp.

References _device_name, and LL_FOREACH.

Referenced by stream_command().

Here is the caller graph for this function:

◆ get_instance_id()

int Mavlink::get_instance_id ( ) const
inline

Definition at line 356 of file mavlink_main.h.

References tap_esc_common::enable_flow_control().

Referenced by get_instance(), MavlinkReceiver::handle_message_manual_control(), and MavlinkReceiver::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_logbuffer()

ringbuffer::RingBuffer* Mavlink::get_logbuffer ( )
inline

Definition at line 455 of file mavlink_main.h.

Referenced by MavlinkStreamStatustext::get_size(), and MavlinkStreamStatustext::send().

Here is the caller graph for this function:

◆ get_main_loop_delay()

unsigned Mavlink::get_main_loop_delay ( ) const
inline

Definition at line 490 of file mavlink_main.h.

Referenced by MavlinkStream::update().

Here is the caller graph for this function:

◆ 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

Definition at line 319 of file mavlink_main.h.

Referenced by MavlinkReceiver::handle_message_manual_control().

Here is the caller graph for this function:

◆ get_mavlink_log_pub()

orb_advert_t* Mavlink::get_mavlink_log_pub ( )
inline

Definition at line 369 of file mavlink_main.h.

◆ get_mode()

enum MAVLINK_MODE Mavlink::get_mode ( )
inline

Definition at line 252 of file mavlink_main.h.

References _mode.

Referenced by MavlinkMissionManager::check_active_mission(), MavlinkMissionManager::send(), and set_boot_complete().

Here is the caller graph for this function:

◆ get_ping_statistics()

struct ping_statistics_s& Mavlink::get_ping_statistics ( )
inline

Get the ping statistics of this MAVLink link.

Definition at line 533 of file mavlink_main.h.

Referenced by MavlinkReceiver::handle_message_ping().

Here is the caller graph for this function:

◆ get_protocol()

Protocol Mavlink::get_protocol ( ) const
inline

Definition at line 459 of file mavlink_main.h.

References linux_pwm_out::_protocol.

Referenced by check_requested_subscriptions(), get_free_tx_buf(), MavlinkReceiver::Run(), MavlinkParametersManager::send(), send_bytes(), send_packet(), serial_instance_exists(), set_boot_complete(), and task_main().

Here is the caller graph for this function:

◆ get_rate_mult()

float Mavlink::get_rate_mult ( ) const
inline

Definition at line 415 of file mavlink_main.h.

Referenced by MavlinkStream::update().

Here is the caller graph for this function:

◆ 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

Definition at line 1477 of file mavlink_main.cpp.

References _mavlink_shell, and MavlinkShell::start().

Referenced by MavlinkReceiver::handle_message_serial_control().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_socket_fd()

int Mavlink::get_socket_fd ( )
inline

Definition at line 461 of file mavlink_main.h.

Referenced by MavlinkReceiver::Run().

Here is the caller graph for this function:

◆ get_start_time()

uint64_t Mavlink::get_start_time ( )
inline

Definition at line 481 of file mavlink_main.h.

Referenced by MavlinkReceiver::Run().

Here is the caller graph for this function:

◆ get_status()

mavlink_status_t* Mavlink::get_status ( )
inline

Definition at line 148 of file mavlink_main.h.

References msg.

Referenced by mavlink_get_channel_status(), MavlinkReceiver::Run(), and set_proto_version().

Here is the caller graph for this function:

◆ get_status_all_instances()

int Mavlink::get_status_all_instances ( bool  show_streams_status)
static

Definition at line 401 of file mavlink_main.cpp.

References _mavlink_instances, display_status(), display_status_streams(), and next.

Referenced by mavlink_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_streams()

List<MavlinkStream *>& Mavlink::get_streams ( )
inline

Definition at line 413 of file mavlink_main.h.

Referenced by MavlinkReceiver::get_message_interval().

Here is the caller graph for this function:

◆ get_system_id()

int Mavlink::get_system_id ( ) const
inline

Get the MAVLink system id.

Returns
The system ID of this vehicle

Definition at line 176 of file mavlink_main.h.

References mavlink_system.

Referenced by MavlinkFTP::_getServerSystemId(), MavlinkReceiver::handle_message_manual_control(), and MavlinkReceiver::handle_message_rc_channels_override().

Here is the caller graph for this function:

◆ get_system_type()

unsigned Mavlink::get_system_type ( )
inline

Definition at line 457 of file mavlink_main.h.

Referenced by MavlinkReceiver::fill_thrust(), MavlinkStreamHighLatency2::send(), MavlinkStreamHeartbeat::send(), and MavlinkStreamHILActuatorControls::send().

Here is the caller graph for this function:

◆ get_telemetry_status()

telemetry_status_s& Mavlink::get_telemetry_status ( )
inline

Get the receive status of this MAVLink link.

Definition at line 449 of file mavlink_main.h.

Referenced by MavlinkReceiver::handle_message_heartbeat().

Here is the caller graph for this function:

◆ get_uart_fd() [1/2]

int Mavlink::get_uart_fd ( unsigned  index)
static

Definition at line 491 of file mavlink_main.cpp.

References get_instance(), and get_uart_fd().

Referenced by get_uart_fd(), and MavlinkReceiver::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_uart_fd() [2/2]

int Mavlink::get_uart_fd ( ) const
inline

Definition at line 169 of file mavlink_main.h.

◆ get_ulog_streaming()

MavlinkULog* Mavlink::get_ulog_streaming ( )
inline

get ulog streaming if active, nullptr otherwise

Definition at line 499 of file mavlink_main.h.

Referenced by MavlinkReceiver::handle_message_logging_ack().

Here is the caller graph for this function:

◆ get_use_hil_gps()

bool Mavlink::get_use_hil_gps ( )
inline

Definition at line 256 of file mavlink_main.h.

Referenced by MavlinkReceiver::handle_message().

Here is the caller graph for this function:

◆ get_wait_to_transmit()

bool Mavlink::get_wait_to_transmit ( )
inline

Definition at line 423 of file mavlink_main.h.

◆ handle_message()

void Mavlink::handle_message ( const mavlink_message_t *  msg)

Definition at line 1137 of file mavlink_main.cpp.

References forward_message(), and get_forwarding_on().

Referenced by MavlinkReceiver::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ hash_check_enabled()

bool Mavlink::hash_check_enabled ( ) const
inline

Definition at line 516 of file mavlink_main.h.

Referenced by MavlinkParametersManager::handle_message().

Here is the caller graph for this function:

◆ instance_count()

int Mavlink::instance_count ( )
static

Definition at line 301 of file mavlink_main.cpp.

References LL_FOREACH.

Referenced by set_instance_id(), and start().

Here is the caller graph for this function:

◆ is_connected()

bool Mavlink::is_connected ( )
inline

Definition at line 264 of file mavlink_main.h.

References hrt_elapsed_time().

Referenced by MavlinkStreamStatustext::send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ is_usb_uart()

bool Mavlink::is_usb_uart ( )
inline

Definition at line 485 of file mavlink_main.h.

Referenced by MavlinkParametersManager::send().

Here is the caller graph for this function:

◆ lockMessageBufferMutex()

void Mavlink::lockMessageBufferMutex ( void  )
inline

Definition at line 428 of file mavlink_main.h.

◆ mavlink_mode_str()

static const char* Mavlink::mavlink_mode_str ( enum MAVLINK_MODE  mode)
inlinestatic

Definition at line 214 of file mavlink_main.h.

Referenced by display_status(), and task_main().

Here is the caller graph for this function:

◆ mavlink_open_uart()

int Mavlink::mavlink_open_uart ( const int  baudrate = DEFAULT_BAUD_RATE,
const char *  uart_name = DEFAULT_DEVICE_NAME,
const bool  force_flow_control = false 
)
private

Definition at line 503 of file mavlink_main.cpp.

References _baudrate, _is_usb_uart, _uart_fd, B1000000, B460800, B500000, B921600, enable_flow_control(), FLOW_CONTROL_AUTO, FLOW_CONTROL_ON, hrt_absolute_time(), ORB_ID, and set_telemetry_status_type().

Referenced by task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ mavlink_update_parameters()

void Mavlink::mavlink_update_parameters ( )
private

Definition at line 215 of file mavlink_main.cpp.

References _protocol_version_switch, and set_proto_version().

Referenced by Mavlink(), and task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ message_buffer_count()

◆ message_buffer_destroy()

void Mavlink::message_buffer_destroy ( )
private

Definition at line 1383 of file mavlink_main.cpp.

References _message_buffer, Mavlink::mavlink_message_buffer::data, Mavlink::mavlink_message_buffer::read_ptr, Mavlink::mavlink_message_buffer::size, and Mavlink::mavlink_message_buffer::write_ptr.

Referenced by task_main().

Here is the caller graph for this function:

◆ message_buffer_get_ptr()

int Mavlink::message_buffer_get_ptr ( void **  ptr,
bool *  is_part 
)
private

Definition at line 1438 of file mavlink_main.cpp.

References _message_buffer, Mavlink::mavlink_message_buffer::data, Mavlink::mavlink_message_buffer::read_ptr, Mavlink::mavlink_message_buffer::size, and Mavlink::mavlink_message_buffer::write_ptr.

Referenced by task_main().

Here is the caller graph for this function:

◆ message_buffer_init()

int Mavlink::message_buffer_init ( int  size)
private

Definition at line 1362 of file mavlink_main.cpp.

References _message_buffer, Mavlink::mavlink_message_buffer::data, OK, Mavlink::mavlink_message_buffer::read_ptr, Mavlink::mavlink_message_buffer::size, and Mavlink::mavlink_message_buffer::write_ptr.

Referenced by task_main().

Here is the caller graph for this function:

◆ message_buffer_is_empty()

int Mavlink::message_buffer_is_empty ( ) const
inlineprivate

Definition at line 717 of file mavlink_main.h.

◆ message_buffer_mark_read()

void Mavlink::message_buffer_mark_read ( int  n)
inlineprivate

Definition at line 721 of file mavlink_main.h.

Referenced by task_main().

Here is the caller graph for this function:

◆ message_buffer_write()

bool Mavlink::message_buffer_write ( const void *  ptr,
int  size 
)

Definition at line 1404 of file mavlink_main.cpp.

References _message_buffer, Mavlink::mavlink_message_buffer::data, Mavlink::mavlink_message_buffer::read_ptr, Mavlink::mavlink_message_buffer::size, and Mavlink::mavlink_message_buffer::write_ptr.

Referenced by pass_message().

Here is the caller graph for this function:

◆ new_instance()

static Mavlink* Mavlink::new_instance ( )
static

◆ odometry_loopback_enabled()

bool Mavlink::odometry_loopback_enabled ( ) const
inline

Definition at line 518 of file mavlink_main.h.

Referenced by MavlinkStreamOdometry::send().

Here is the caller graph for this function:

◆ operator=()

Mavlink Mavlink::operator= ( const Mavlink )
privatedelete

◆ pass_message()

void Mavlink::pass_message ( const mavlink_message_t *  msg)
private

Definition at line 1465 of file mavlink_main.cpp.

References _forwarding_on, _message_buffer_mutex, and message_buffer_write().

Referenced by forward_message().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ publish_telemetry_status()

void Mavlink::publish_telemetry_status ( )
private

Definition at line 2595 of file mavlink_main.cpp.

References _datarate, _mode, _protocol_version, _rate_mult, _streams, _telem_status_pub, _tstatus, telemetry_status_s::data_rate, telemetry_status_s::flow_control, telemetry_status_s::forwarding, telemetry_status_s::ftp, ftp_enabled(), get_flow_control_enabled(), get_forwarding_on(), hrt_absolute_time(), telemetry_status_s::mavlink_v2, telemetry_status_s::mode, uORB::PublicationQueued< T >::publish(), telemetry_status_s::rate_multiplier, List::size(), telemetry_status_s::streams, and telemetry_status_s::timestamp.

Referenced by task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ request_stop_ulog_streaming()

void Mavlink::request_stop_ulog_streaming ( )
inline

Definition at line 506 of file mavlink_main.h.

References fd.

Referenced by MavlinkReceiver::handle_message_command_both().

Here is the caller graph for this function:

◆ resend_message()

void Mavlink::resend_message ( mavlink_message_t *  msg)
inline

Resend message as is, don't change sequence number and CRC.

Definition at line 343 of file mavlink_main.h.

Referenced by task_main().

Here is the caller graph for this function:

◆ send_autopilot_capabilites()

void Mavlink::send_autopilot_capabilites ( )

Send the capabilities of this autopilot in terms of the MAVLink spec.

Definition at line 1168 of file mavlink_main.cpp.

References add_orb_subscription(), CONFIG_CDCACM_PRODUCTID, get_channel(), mavlink_system, msg, ORB_ID, px4_board_version(), px4_firmware_vendor_version(), px4_firmware_version(), px4_firmware_version_binary(), px4_os_version(), and px4_os_version_binary().

Referenced by MavlinkReceiver::handle_message_command_both(), and task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ 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.

Definition at line 852 of file mavlink_main.cpp.

References _interface_name, _last_write_success_time, _last_write_try_time, _mavlink_start_time, _socket_fd, _uart_fd, count_txbytes(), count_txerrbytes(), get_free_tx_buf(), get_protocol(), hrt_absolute_time(), SERIAL, and write().

Referenced by mavlink_send_uart_bytes().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ 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

Definition at line 790 of file mavlink_main.cpp.

References _mode, _send_mutex, _socket_fd, _tstatus, get_protocol(), telemetry_status_s::heartbeat_time, hrt_elapsed_time(), and MAVLINK_MODE_ONBOARD.

Referenced by mavlink_end_uart_send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ send_protocol_version()

void Mavlink::send_protocol_version ( )

Send the protocol version of MAVLink.

Definition at line 1236 of file mavlink_main.cpp.

References _protocol_version, get_channel(), msg, px4_mavlink_lib_version_binary(), and set_proto_version().

Referenced by MavlinkReceiver::handle_message_command_both().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ 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()

◆ 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)

Definition at line 1162 of file mavlink_main.cpp.

References _mavlink_log_pub, and mavlink_log_emergency.

◆ 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)

Definition at line 1150 of file mavlink_main.cpp.

References _mavlink_log_pub, and mavlink_log_info.

Referenced by MavlinkParametersManager::handle_message().

Here is the caller graph for this function:

◆ serial_instance_exists()

bool Mavlink::serial_instance_exists ( const char *  device_name,
Mavlink self 
)
static

Definition at line 428 of file mavlink_main.cpp.

References _device_name, _mavlink_instances, get_protocol(), next, and SERIAL.

Referenced by task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ 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.

Definition at line 2997 of file mavlink_main.cpp.

References _boot_complete, get_mode(), get_protocol(), LL_FOREACH, and MAVLINK_MODE_ONBOARD.

Referenced by mavlink_main(), and MavlinkReceiver::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_channel()

void Mavlink::set_channel ( )
private

Definition at line 234 of file mavlink_main.cpp.

References _channel, and _instance_id.

Referenced by task_main().

Here is the caller graph for this function:

◆ set_data_rate()

void Mavlink::set_data_rate ( int  rate)
inline

Definition at line 488 of file mavlink_main.h.

Referenced by MavlinkReceiver::set_message_interval().

Here is the caller graph for this function:

◆ set_has_received_messages()

void Mavlink::set_has_received_messages ( bool  received_messages)
inline

Definition at line 420 of file mavlink_main.h.

Referenced by MavlinkReceiver::handle_message().

Here is the caller graph for this function:

◆ 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.

Definition at line 718 of file mavlink_main.cpp.

References _datarate, _hil_enabled, configure_stream(), f(), and OK.

Referenced by task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_instance_id()

void Mavlink::set_instance_id ( )
private

Definition at line 280 of file mavlink_main.cpp.

References _instance_id, and instance_count().

Referenced by task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ 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

Definition at line 307 of file mavlink_main.h.

Referenced by task_main().

Here is the caller graph for this function:

◆ set_proto_version()

void Mavlink::set_proto_version ( unsigned  version)

Set the MAVLink version.

Currently supporting v1 and v2

Parameters
versionMAVLink version

Definition at line 286 of file mavlink_main.cpp.

References _protocol_version, _protocol_version_switch, and get_status().

Referenced by mavlink_update_parameters(), MavlinkReceiver::Run(), and send_protocol_version().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_protocol()

void Mavlink::set_protocol ( Protocol  p)
inline

Set communication protocol for this mavlink instance.

Definition at line 312 of file mavlink_main.h.

References linux_pwm_out::_protocol.

Referenced by task_main().

Here is the caller graph for this function:

◆ set_telemetry_status_type()

void Mavlink::set_telemetry_status_type ( uint8_t  type)
inline

Definition at line 451 of file mavlink_main.h.

Referenced by mavlink_open_uart(), task_main(), update_radio_status(), and update_rate_mult().

Here is the caller graph for this function:

◆ set_uorb_main_fd()

void Mavlink::set_uorb_main_fd ( int  fd,
unsigned int  interval 
)

◆ set_wait_to_transmit()

void Mavlink::set_wait_to_transmit ( bool  wait)
inline

Definition at line 422 of file mavlink_main.h.

◆ should_transmit()

bool Mavlink::should_transmit ( )
inline

Definition at line 424 of file mavlink_main.h.

Referenced by MavlinkStreamHighLatency2::send(), and task_main().

Here is the caller graph for this function:

◆ start()

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

Start the mavlink task.

Returns
OK on success.

Definition at line 2690 of file mavlink_main.cpp.

References MavlinkCommandSender::initialize(), MavlinkULog::initialize(), instance_count(), MAVLINK_MAX_INSTANCES, MAVLINK_NET_ADDED_STACK, and start_helper().

Referenced by mavlink_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start_helper()

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

Definition at line 2666 of file mavlink_main.cpp.

References _task_running, ll40ls::instance, Mavlink(), and task_main().

Referenced by start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ stream_command()

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

Definition at line 2872 of file mavlink_main.cpp.

References configure_stream_threadsafe(), DEFAULT_DEVICE_NAME, device_name, f(), get_instance_for_device(), OK, and usage().

Referenced by mavlink_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ task_main()

int Mavlink::task_main ( int  argc,
char *  argv[] 
)
private

Main mavlink task.

Definition at line 1834 of file mavlink_main.cpp.

References _baudrate, _bytes_rx, _bytes_timestamp, _bytes_tx, _bytes_txerr, _channel, _datarate, _device_name, _first_heartbeat_sent, _forwarding_on, _ftp_on, _interface_name, _is_usb_uart, _logbuffer, _loop_interval_perf, _main_loop_delay, _mavlink_log_pub, _mavlink_shell, _mavlink_ulog, _mavlink_ulog_stop_requested, _message_buffer_mutex, _mode, _receive_thread, _send_mutex, _socket_fd, _streams, _subscribe_to_stream, _subscriptions, _task_should_exit, _transmitting_enabled, _transmitting_enabled_commanded, _tstatus, _uart_fd, _wait_to_transmit, add_orb_subscription(), MavlinkShell::available(), BROADCAST_MODE_MULTICAST, check_radio_config(), check_requested_subscriptions(), List::clear(), configure_stream(), configure_streams_to_default(), dt, f(), get_channel(), get_free_tx_buf(), get_protocol(), MavlinkULog::handle_update(), telemetry_status_s::heartbeat_time, vehicle_status_s::high_latency_data_link_lost, vehicle_status_s::hil_state, hrt_absolute_time(), hrt_abstime, hrt_elapsed_time(), LL_APPEND, MAIN_LOOP_DELAY, mavlink_and_console_log_info, MAVLINK_MAX_INTERVAL, MAVLINK_MIN_INTERVAL, MAVLINK_MODE_CONFIG, MAVLINK_MODE_COUNT, MAVLINK_MODE_CUSTOM, MAVLINK_MODE_EXTVISION, MAVLINK_MODE_EXTVISIONMIN, MAVLINK_MODE_IRIDIUM, MAVLINK_MODE_MAGIC, MAVLINK_MODE_MINIMAL, MAVLINK_MODE_NORMAL, MAVLINK_MODE_ONBOARD, MAVLINK_MODE_OSD, mavlink_mode_str(), mavlink_open_uart(), mavlink_update_parameters(), MAX_DATA_RATE, message_buffer_destroy(), message_buffer_get_ptr(), message_buffer_init(), message_buffer_mark_read(), msg, OK, ORB_ID, perf_begin(), perf_count(), perf_end(), publish_telemetry_status(), telemetry_status_s::rate_rx, telemetry_status_s::rate_tx, telemetry_status_s::rate_txerr, vehicle_status_s::rc_input_mode, MavlinkShell::read(), MavlinkReceiver::receive_start(), resend_message(), send_autopilot_capabilites(), SERIAL, serial_instance_exists(), set_channel(), set_hil_enabled(), set_instance_id(), set_manual_input_mode_generation(), set_protocol(), set_telemetry_status_type(), should_transmit(), MavlinkULog::start_ack_received(), status, MavlinkULog::stop(), MavlinkOrbSubscription::subscribe_from_beginning(), vehicle_command_ack_s::timestamp, telemetry_status_s::timestamp, MavlinkOrbSubscription::update(), MavlinkOrbSubscription::update_if_changed(), update_rate_mult(), and usage().

Referenced by start_helper().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ try_start_ulog_streaming()

void Mavlink::try_start_ulog_streaming ( uint8_t  target_system,
uint8_t  target_component 
)
inline

Definition at line 500 of file mavlink_main.h.

References f(), and MavlinkULog::try_start().

Referenced by MavlinkReceiver::handle_message_command_both().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ unlockMessageBufferMutex()

void Mavlink::unlockMessageBufferMutex ( void  )
inline

Definition at line 429 of file mavlink_main.h.

◆ update_radio_status()

void Mavlink::update_radio_status ( const radio_status_s radio_status)

Definition at line 1567 of file mavlink_main.cpp.

References _radio_status_available, _radio_status_critical, _radio_status_mult, _rstatus, RADIO_BUFFER_CRITICAL_LOW_PERCENTAGE, RADIO_BUFFER_HALF_PERCENTAGE, RADIO_BUFFER_LOW_PERCENTAGE, set_telemetry_status_type(), and radio_status_s::txbuf.

Referenced by MavlinkReceiver::handle_message_radio_status().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_rate_mult()

void Mavlink::update_rate_mult ( )
private

Update rate mult so total bitrate will be equal to _datarate.

Definition at line 1509 of file mavlink_main.cpp.

References _datarate, _instance_id, _mavlink_ulog, _radio_status_available, _radio_status_critical, _radio_status_mult, _rate_mult, _rstatus, _streams, _tstatus, math::constrain(), MavlinkULog::current_data_rate(), f(), get_flow_control_enabled(), hrt_elapsed_time(), telemetry_status_s::rate_tx, telemetry_status_s::rate_txerr, set_telemetry_status_type(), and radio_status_s::timestamp.

Referenced by task_main().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _baudrate

int Mavlink::_baudrate {57600}
private

Definition at line 591 of file mavlink_main.h.

Referenced by display_status(), mavlink_open_uart(), and task_main().

◆ _boot_complete

bool Mavlink::_boot_complete = false
staticprivate

Definition at line 552 of file mavlink_main.h.

Referenced by mavlink_get_channel_buffer(), and set_boot_complete().

◆ _bytes_rx

unsigned Mavlink::_bytes_rx {0}
private

Definition at line 622 of file mavlink_main.h.

Referenced by task_main().

◆ _bytes_timestamp

uint64_t Mavlink::_bytes_timestamp {0}
private

Definition at line 623 of file mavlink_main.h.

Referenced by task_main().

◆ _bytes_tx

unsigned Mavlink::_bytes_tx {0}
private

Definition at line 620 of file mavlink_main.h.

Referenced by task_main().

◆ _bytes_txerr

unsigned Mavlink::_bytes_txerr {0}
private

Definition at line 621 of file mavlink_main.h.

Referenced by task_main().

◆ _channel

mavlink_channel_t Mavlink::_channel {MAVLINK_COMM_0}
private

Definition at line 580 of file mavlink_main.h.

Referenced by display_status(), set_channel(), and task_main().

◆ _datarate

int Mavlink::_datarate {1000}
private

data rate for normal streams (attitude, position, etc.)

Definition at line 592 of file mavlink_main.h.

Referenced by display_status(), publish_telemetry_status(), set_hil_enabled(), task_main(), and update_rate_mult().

◆ _device_name

const char* Mavlink::_device_name {DEFAULT_DEVICE_NAME}

◆ _first_heartbeat_sent

bool Mavlink::_first_heartbeat_sent {false}
private

Definition at line 545 of file mavlink_main.h.

Referenced by task_main().

◆ _first_start_time

hrt_abstime Mavlink::_first_start_time = {0}
staticprivate

Definition at line 693 of file mavlink_main.h.

Referenced by Mavlink(), and mavlink_get_channel_buffer().

◆ _flow_control_mode

FLOW_CONTROL_MODE Mavlink::_flow_control_mode {Mavlink::FLOW_CONTROL_OFF}
private

Definition at line 612 of file mavlink_main.h.

Referenced by display_status(), enable_flow_control(), and get_free_tx_buf().

◆ _forwarding_on

bool Mavlink::_forwarding_on {false}
private

Definition at line 586 of file mavlink_main.h.

Referenced by pass_message(), and task_main().

◆ _ftp_on

bool Mavlink::_ftp_on {false}
private

Definition at line 587 of file mavlink_main.h.

Referenced by display_status(), and task_main().

◆ _generate_rc

bool Mavlink::_generate_rc {false}
private

Generate RC messages from manual input MAVLink messages.

Definition at line 563 of file mavlink_main.h.

◆ _hil_enabled

bool Mavlink::_hil_enabled {false}
private

Hardware In the Loop mode.

Definition at line 562 of file mavlink_main.h.

Referenced by set_hil_enabled().

◆ _instance_id

int Mavlink::_instance_id {0}
private

Definition at line 541 of file mavlink_main.h.

Referenced by set_channel(), set_instance_id(), and update_rate_mult().

◆ _interface_name

const char* Mavlink::_interface_name {nullptr}
private

Definition at line 641 of file mavlink_main.h.

Referenced by send_bytes(), and task_main().

◆ _is_usb_uart

bool Mavlink::_is_usb_uart {false}
private

Port is USB.

Definition at line 564 of file mavlink_main.h.

Referenced by enable_flow_control(), mavlink_open_uart(), and task_main().

◆ _last_write_success_time

uint64_t Mavlink::_last_write_success_time {0}
private

Definition at line 614 of file mavlink_main.h.

Referenced by get_free_tx_buf(), and send_bytes().

◆ _last_write_try_time

uint64_t Mavlink::_last_write_try_time {0}
private

Definition at line 615 of file mavlink_main.h.

Referenced by get_free_tx_buf(), and send_bytes().

◆ _logbuffer

ringbuffer::RingBuffer Mavlink::_logbuffer {5, sizeof(mavlink_log_s)}
private

Definition at line 582 of file mavlink_main.h.

Referenced by task_main().

◆ _loop_interval_perf

perf_counter_t Mavlink::_loop_interval_perf {perf_alloc(PC_INTERVAL, "mavlink_int")}
private

loop performance counter

loop interval performance counter

Definition at line 681 of file mavlink_main.h.

Referenced by task_main(), and ~Mavlink().

◆ _main_loop_delay

unsigned Mavlink::_main_loop_delay {1000}
private

mainloop delay, depends on data rate

Definition at line 568 of file mavlink_main.h.

Referenced by task_main().

◆ _mavlink_buffer

mavlink_message_t Mavlink::_mavlink_buffer {}
private

Definition at line 558 of file mavlink_main.h.

◆ _mavlink_link_termination_allowed

bool Mavlink::_mavlink_link_termination_allowed {false}
private

Definition at line 606 of file mavlink_main.h.

◆ _mavlink_log_pub

orb_advert_t Mavlink::_mavlink_log_pub {nullptr}
private

◆ _mavlink_param_queue_index

unsigned int Mavlink::_mavlink_param_queue_index {0}
private

If the queue index is not at 0, the queue sending logic will send parameters from the current index to len - 1, the end of the param list.

Definition at line 604 of file mavlink_main.h.

◆ _mavlink_shell

MavlinkShell* Mavlink::_mavlink_shell {nullptr}
private

Definition at line 573 of file mavlink_main.h.

Referenced by close_shell(), get_shell(), and task_main().

◆ _mavlink_start_time

uint64_t Mavlink::_mavlink_start_time {0}
private

Definition at line 616 of file mavlink_main.h.

Referenced by send_bytes().

◆ _mavlink_status

mavlink_status_t Mavlink::_mavlink_status {}
private

Definition at line 559 of file mavlink_main.h.

◆ _mavlink_ulog

MavlinkULog* Mavlink::_mavlink_ulog {nullptr}
private

Definition at line 574 of file mavlink_main.h.

Referenced by display_status(), task_main(), and update_rate_mult().

◆ _mavlink_ulog_stop_requested

volatile bool Mavlink::_mavlink_ulog_stop_requested {false}
private

Definition at line 576 of file mavlink_main.h.

Referenced by task_main().

◆ _message_buffer

◆ _message_buffer_mutex

pthread_mutex_t Mavlink::_message_buffer_mutex {}
private

Definition at line 660 of file mavlink_main.h.

Referenced by pass_message(), and task_main().

◆ _mode

◆ _ping_stats

ping_statistics_s Mavlink::_ping_stats {}
private

Definition at line 649 of file mavlink_main.h.

Referenced by display_status().

◆ _protocol

Protocol Mavlink::_protocol {Protocol::SERIAL}
private

Definition at line 644 of file mavlink_main.h.

Referenced by display_status().

◆ _protocol_version

int32_t Mavlink::_protocol_version {0}
private

◆ _protocol_version_switch

int32_t Mavlink::_protocol_version_switch {-1}
private

Definition at line 617 of file mavlink_main.h.

Referenced by mavlink_update_parameters(), and set_proto_version().

◆ _radio_status_available

bool Mavlink::_radio_status_available {false}
private

Definition at line 595 of file mavlink_main.h.

Referenced by update_radio_status(), and update_rate_mult().

◆ _radio_status_critical

bool Mavlink::_radio_status_critical {false}
private

Definition at line 596 of file mavlink_main.h.

Referenced by update_radio_status(), and update_rate_mult().

◆ _radio_status_mult

float Mavlink::_radio_status_mult {1.0f}
private

Definition at line 597 of file mavlink_main.h.

Referenced by update_radio_status(), and update_rate_mult().

◆ _rate_mult

float Mavlink::_rate_mult {1.0f}
private

◆ _receive_thread

pthread_t Mavlink::_receive_thread {}
private

Definition at line 584 of file mavlink_main.h.

Referenced by task_main().

◆ _received_messages

bool Mavlink::_received_messages {false}
private

Whether we've received valid mavlink messages.

Definition at line 566 of file mavlink_main.h.

◆ _rstatus

radio_status_s Mavlink::_rstatus {}
private

Definition at line 646 of file mavlink_main.h.

Referenced by display_status(), update_radio_status(), and update_rate_mult().

◆ _send_mutex

pthread_mutex_t Mavlink::_send_mutex {}
private

Definition at line 661 of file mavlink_main.h.

Referenced by send_packet(), and task_main().

◆ _socket_fd

int Mavlink::_socket_fd {-1}
private

Definition at line 643 of file mavlink_main.h.

Referenced by send_bytes(), send_packet(), and task_main().

◆ _streams

List<MavlinkStream *> Mavlink::_streams
private

◆ _subscribe_to_stream

char* Mavlink::_subscribe_to_stream {nullptr}
private

◆ _subscribe_to_stream_rate

float Mavlink::_subscribe_to_stream_rate {0.0f}
private

rate of stream to subscribe to (0=disable, -1=unlimited, -2=default)

Definition at line 609 of file mavlink_main.h.

Referenced by check_requested_subscriptions(), and configure_stream_threadsafe().

◆ _subscriptions

List<MavlinkOrbSubscription *> Mavlink::_subscriptions
private

Definition at line 570 of file mavlink_main.h.

Referenced by add_orb_subscription(), and task_main().

◆ _task_running

bool Mavlink::_task_running {true}
private

Definition at line 551 of file mavlink_main.h.

Referenced by destroy_all_instances(), start_helper(), and ~Mavlink().

◆ _task_should_exit

bool Mavlink::_task_should_exit {false}

Mavlink task should exit iff true.

Definition at line 463 of file mavlink_main.h.

Referenced by configure_stream_threadsafe(), destroy_all_instances(), MavlinkReceiver::Run(), task_main(), and ~Mavlink().

◆ _telem_status_pub

uORB::PublicationQueued<telemetry_status_s> Mavlink::_telem_status_pub {ORB_ID(telemetry_status)}
private

Definition at line 549 of file mavlink_main.h.

Referenced by publish_telemetry_status().

◆ _transmitting_enabled

bool Mavlink::_transmitting_enabled {true}
private

Definition at line 543 of file mavlink_main.h.

Referenced by display_status(), and task_main().

◆ _transmitting_enabled_commanded

bool Mavlink::_transmitting_enabled_commanded {false}
private

Definition at line 544 of file mavlink_main.h.

Referenced by task_main().

◆ _tstatus

◆ _uart_fd

int Mavlink::_uart_fd {-1}
private

◆ _udp_initialised

bool Mavlink::_udp_initialised {false}
private

Definition at line 610 of file mavlink_main.h.

◆ _wait_to_transmit

bool Mavlink::_wait_to_transmit {false}
private

Wait to transmit until received messages.

Definition at line 565 of file mavlink_main.h.

Referenced by task_main().

◆ MAVLINK_MAX_INSTANCES

constexpr int Mavlink::MAVLINK_MAX_INSTANCES {4}
staticprivate

Definition at line 553 of file mavlink_main.h.

Referenced by start().

◆ MAVLINK_MAX_INTERVAL

constexpr int Mavlink::MAVLINK_MAX_INTERVAL {10000}
staticprivate

Definition at line 555 of file mavlink_main.h.

Referenced by task_main().

◆ MAVLINK_MIN_INTERVAL

constexpr int Mavlink::MAVLINK_MIN_INTERVAL {1500}
staticprivate

Definition at line 554 of file mavlink_main.h.

Referenced by task_main().

◆ MAVLINK_MIN_MULTIPLIER

constexpr float Mavlink::MAVLINK_MIN_MULTIPLIER {0.0005f}
staticprivate

Definition at line 556 of file mavlink_main.h.

◆ next

Mavlink* Mavlink::next {nullptr}
protected

◆ RADIO_BUFFER_CRITICAL_LOW_PERCENTAGE

constexpr unsigned Mavlink::RADIO_BUFFER_CRITICAL_LOW_PERCENTAGE = 25
staticprivate

Definition at line 689 of file mavlink_main.h.

Referenced by update_radio_status().

◆ RADIO_BUFFER_HALF_PERCENTAGE

constexpr unsigned Mavlink::RADIO_BUFFER_HALF_PERCENTAGE = 50
staticprivate

Definition at line 691 of file mavlink_main.h.

Referenced by update_radio_status().

◆ RADIO_BUFFER_LOW_PERCENTAGE

constexpr unsigned Mavlink::RADIO_BUFFER_LOW_PERCENTAGE = 35
staticprivate

Definition at line 690 of file mavlink_main.h.

Referenced by update_radio_status().


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