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

#include <mavlink_receiver.h>

Inheritance diagram for MavlinkReceiver:
Collaboration diagram for MavlinkReceiver:

Public Member Functions

 MavlinkReceiver (Mavlink *parent)
 
 ~MavlinkReceiver ()=default
 

Static Public Member Functions

static void receive_start (pthread_t *thread, Mavlink *parent)
 Start the receiver thread. More...
 
static void * start_helper (void *context)
 

Private Member Functions

void acknowledge (uint8_t sysid, uint8_t compid, uint16_t command, uint8_t result)
 
template<class T >
void handle_message_command_both (mavlink_message_t *msg, const T &cmd_mavlink, const vehicle_command_s &vehicle_command)
 Common method to handle both mavlink command types. More...
 
void handle_message (mavlink_message_t *msg)
 
void handle_message_adsb_vehicle (mavlink_message_t *msg)
 
void handle_message_att_pos_mocap (mavlink_message_t *msg)
 
void handle_message_battery_status (mavlink_message_t *msg)
 
void handle_message_cellular_status (mavlink_message_t *msg)
 
void handle_message_collision (mavlink_message_t *msg)
 
void handle_message_command_ack (mavlink_message_t *msg)
 
void handle_message_command_int (mavlink_message_t *msg)
 
void handle_message_command_long (mavlink_message_t *msg)
 
void handle_message_debug (mavlink_message_t *msg)
 
void handle_message_debug_float_array (mavlink_message_t *msg)
 
void handle_message_debug_vect (mavlink_message_t *msg)
 
void handle_message_distance_sensor (mavlink_message_t *msg)
 
void handle_message_follow_target (mavlink_message_t *msg)
 
void handle_message_gps_global_origin (mavlink_message_t *msg)
 
void handle_message_gps_rtcm_data (mavlink_message_t *msg)
 
void handle_message_heartbeat (mavlink_message_t *msg)
 
void handle_message_hil_gps (mavlink_message_t *msg)
 
void handle_message_hil_optical_flow (mavlink_message_t *msg)
 
void handle_message_hil_sensor (mavlink_message_t *msg)
 
void handle_message_hil_state_quaternion (mavlink_message_t *msg)
 
void handle_message_landing_target (mavlink_message_t *msg)
 
void handle_message_logging_ack (mavlink_message_t *msg)
 
void handle_message_manual_control (mavlink_message_t *msg)
 
void handle_message_named_value_float (mavlink_message_t *msg)
 
void handle_message_obstacle_distance (mavlink_message_t *msg)
 
void handle_message_odometry (mavlink_message_t *msg)
 
void handle_message_optical_flow_rad (mavlink_message_t *msg)
 
void handle_message_ping (mavlink_message_t *msg)
 
void handle_message_play_tune (mavlink_message_t *msg)
 
void handle_message_radio_status (mavlink_message_t *msg)
 
void handle_message_rc_channels_override (mavlink_message_t *msg)
 
void handle_message_serial_control (mavlink_message_t *msg)
 
void handle_message_set_actuator_control_target (mavlink_message_t *msg)
 
void handle_message_set_attitude_target (mavlink_message_t *msg)
 
void handle_message_set_mode (mavlink_message_t *msg)
 
void handle_message_set_position_target_local_ned (mavlink_message_t *msg)
 
void handle_message_set_position_target_global_int (mavlink_message_t *msg)
 
void handle_message_statustext (mavlink_message_t *msg)
 
void handle_message_trajectory_representation_waypoints (mavlink_message_t *msg)
 
void handle_message_utm_global_position (mavlink_message_t *msg)
 
void handle_message_vision_position_estimate (mavlink_message_t *msg)
 
void handle_message_onboard_computer_status (mavlink_message_t *msg)
 
void Run ()
 Receive data from UART/UDP. More...
 
int set_message_interval (int msgId, float interval, int data_rate=-1)
 Set the interval at which the given message stream is published. More...
 
void get_message_interval (int msgId)
 
switch_pos_t decode_switch_pos (uint16_t buttons, unsigned sw)
 Decode a switch position from a bitfield. More...
 
int decode_switch_pos_n (uint16_t buttons, unsigned sw)
 Decode a switch position from a bitfield and state. More...
 
bool evaluate_target_ok (int command, int target_system, int target_component)
 
void send_flight_information ()
 
void send_storage_information (int storage_id)
 
void fill_thrust (float *thrust_body_array, uint8_t vehicle_type, float thrust)
 
void update_params ()
 Updates the battery, optical flow, and flight ID subscribed parameters. More...
 
 DEFINE_PARAMETERS ((ParamFloat< px4::params::BAT_CRIT_THR >) _param_bat_crit_thr,(ParamFloat< px4::params::BAT_EMERGEN_THR >) _param_bat_emergen_thr,(ParamFloat< px4::params::BAT_LOW_THR >) _param_bat_low_thr,(ParamInt< px4::params::COM_FLIGHT_UUID >) _param_com_flight_uuid,(ParamFloat< px4::params::SENS_FLOW_MAXHGT >) _param_sens_flow_maxhgt,(ParamFloat< px4::params::SENS_FLOW_MAXR >) _param_sens_flow_maxr,(ParamFloat< px4::params::SENS_FLOW_MINHGT >) _param_sens_flow_minhgt,(ParamInt< px4::params::SENS_FLOW_ROT >) _param_sens_flow_rot)
 
 MavlinkReceiver (const MavlinkReceiver &)=delete
 
MavlinkReceiver operator= (const MavlinkReceiver &)=delete
 

Private Attributes

Mavlink_mavlink
 
MavlinkFTP _mavlink_ftp
 
MavlinkLogHandler _mavlink_log_handler
 
MavlinkMissionManager _mission_manager
 
MavlinkParametersManager _parameters_manager
 
MavlinkTimesync _mavlink_timesync
 
mavlink_status_t _status {}
 receiver status, used for mavlink_parse_char() More...
 
uORB::Publication< actuator_controls_s_actuator_controls_pubs [4] {ORB_ID(actuator_controls_0), ORB_ID(actuator_controls_1), ORB_ID(actuator_controls_2), ORB_ID(actuator_controls_3)}
 
uORB::Publication< airspeed_s_airspeed_pub {ORB_ID(airspeed)}
 
uORB::Publication< battery_status_s_battery_pub {ORB_ID(battery_status)}
 
uORB::Publication< cellular_status_s_cellular_status_pub {ORB_ID(cellular_status)}
 
uORB::Publication< collision_report_s_collision_report_pub {ORB_ID(collision_report)}
 
uORB::Publication< debug_array_s_debug_array_pub {ORB_ID(debug_array)}
 
uORB::Publication< debug_key_value_s_debug_key_value_pub {ORB_ID(debug_key_value)}
 
uORB::Publication< debug_value_s_debug_value_pub {ORB_ID(debug_value)}
 
uORB::Publication< debug_vect_s_debug_vect_pub {ORB_ID(debug_vect)}
 
uORB::Publication< follow_target_s_follow_target_pub {ORB_ID(follow_target)}
 
uORB::Publication< landing_target_pose_s_landing_target_pose_pub {ORB_ID(landing_target_pose)}
 
uORB::Publication< log_message_s_log_message_pub {ORB_ID(log_message)}
 
uORB::Publication< obstacle_distance_s_obstacle_distance_pub {ORB_ID(obstacle_distance)}
 
uORB::Publication< offboard_control_mode_s_offboard_control_mode_pub {ORB_ID(offboard_control_mode)}
 
uORB::Publication< onboard_computer_status_s_onboard_computer_status_pub {ORB_ID(onboard_computer_status)}
 
uORB::Publication< optical_flow_s_flow_pub {ORB_ID(optical_flow)}
 
uORB::Publication< position_setpoint_triplet_s_pos_sp_triplet_pub {ORB_ID(position_setpoint_triplet)}
 
uORB::Publication< vehicle_attitude_s_attitude_pub {ORB_ID(vehicle_attitude)}
 
uORB::Publication< vehicle_attitude_setpoint_s_att_sp_pub {ORB_ID(vehicle_attitude_setpoint)}
 
uORB::Publication< vehicle_attitude_setpoint_s_mc_virtual_att_sp_pub {ORB_ID(mc_virtual_attitude_setpoint)}
 
uORB::Publication< vehicle_attitude_setpoint_s_fw_virtual_att_sp_pub {ORB_ID(fw_virtual_attitude_setpoint)}
 
uORB::Publication< vehicle_global_position_s_global_pos_pub {ORB_ID(vehicle_global_position)}
 
uORB::Publication< vehicle_gps_position_s_gps_pub {ORB_ID(vehicle_gps_position)}
 
uORB::Publication< vehicle_land_detected_s_land_detector_pub {ORB_ID(vehicle_land_detected)}
 
uORB::Publication< vehicle_local_position_s_local_pos_pub {ORB_ID(vehicle_local_position)}
 
uORB::Publication< vehicle_odometry_s_mocap_odometry_pub {ORB_ID(vehicle_mocap_odometry)}
 
uORB::Publication< vehicle_odometry_s_visual_odometry_pub {ORB_ID(vehicle_visual_odometry)}
 
uORB::Publication< vehicle_rates_setpoint_s_rates_sp_pub {ORB_ID(vehicle_rates_setpoint)}
 
uORB::Publication< vehicle_trajectory_waypoint_s_trajectory_waypoint_pub {ORB_ID(vehicle_trajectory_waypoint)}
 
uORB::PublicationMulti< distance_sensor_s_distance_sensor_pub {ORB_ID(distance_sensor), ORB_PRIO_LOW}
 
uORB::PublicationMulti< distance_sensor_s_flow_distance_sensor_pub {ORB_ID(distance_sensor), ORB_PRIO_LOW}
 
uORB::PublicationMulti< input_rc_s_rc_pub {ORB_ID(input_rc), ORB_PRIO_LOW}
 
uORB::PublicationMulti< manual_control_setpoint_s_manual_pub {ORB_ID(manual_control_setpoint), ORB_PRIO_LOW}
 
uORB::PublicationMulti< ping_s_ping_pub {ORB_ID(ping), ORB_PRIO_LOW}
 
uORB::PublicationMulti< radio_status_s_radio_status_pub {ORB_ID(radio_status), ORB_PRIO_LOW}
 
uORB::PublicationMulti< sensor_accel_s_accel_pub {ORB_ID(sensor_accel), ORB_PRIO_LOW}
 
uORB::PublicationMulti< sensor_baro_s_baro_pub {ORB_ID(sensor_baro), ORB_PRIO_LOW}
 
uORB::PublicationMulti< sensor_gyro_s_gyro_pub {ORB_ID(sensor_gyro), ORB_PRIO_LOW}
 
uORB::PublicationMulti< sensor_mag_s_mag_pub {ORB_ID(sensor_mag), ORB_PRIO_LOW}
 
uORB::PublicationQueued< gps_inject_data_s_gps_inject_data_pub {ORB_ID(gps_inject_data)}
 
uORB::PublicationQueued< transponder_report_s_transponder_report_pub {ORB_ID(transponder_report)}
 
uORB::PublicationQueued< vehicle_command_ack_s_cmd_ack_pub {ORB_ID(vehicle_command_ack)}
 
uORB::PublicationQueued< vehicle_command_s_cmd_pub {ORB_ID(vehicle_command)}
 
uORB::Subscription _actuator_armed_sub {ORB_ID(actuator_armed)}
 
uORB::Subscription _control_mode_sub {ORB_ID(vehicle_control_mode)}
 
uORB::Subscription _parameter_update_sub {ORB_ID(parameter_update)}
 
uORB::Subscription _vehicle_attitude_sub {ORB_ID(vehicle_attitude)}
 
uORB::Subscription _vehicle_local_position_sub {ORB_ID(vehicle_local_position)}
 
uORB::Subscription _vehicle_status_sub {ORB_ID(vehicle_status)}
 
uint8_t _mom_switch_pos [MOM_SWITCH_COUNT] {}
 
uint16_t _mom_switch_state {0}
 
uint64_t _global_ref_timestamp {0}
 
map_projection_reference_s _hil_local_proj_ref {}
 
float _hil_local_alt0 {0.0f}
 
bool _hil_local_proj_inited {false}
 
hrt_abstime _last_utm_global_pos_com {0}
 

Static Private Attributes

static constexpr unsigned int MOM_SWITCH_COUNT {8}
 

Detailed Description

Definition at line 106 of file mavlink_receiver.h.

Constructor & Destructor Documentation

◆ MavlinkReceiver() [1/2]

MavlinkReceiver::MavlinkReceiver ( Mavlink parent)

Definition at line 80 of file mavlink_receiver.cpp.

◆ ~MavlinkReceiver()

MavlinkReceiver::~MavlinkReceiver ( )
default

◆ MavlinkReceiver() [2/2]

MavlinkReceiver::MavlinkReceiver ( const MavlinkReceiver )
privatedelete

Member Function Documentation

◆ acknowledge()

void MavlinkReceiver::acknowledge ( uint8_t  sysid,
uint8_t  compid,
uint16_t  command,
uint8_t  result 
)
private

Definition at line 92 of file mavlink_receiver.cpp.

References _cmd_ack_pub, command, hrt_absolute_time(), uORB::PublicationQueued< T >::publish(), and vehicle_command_ack_s::timestamp.

Referenced by handle_message_command_both().

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

◆ decode_switch_pos()

switch_pos_t MavlinkReceiver::decode_switch_pos ( uint16_t  buttons,
unsigned  sw 
)
private

Decode a switch position from a bitfield.

Definition at line 1777 of file mavlink_receiver.cpp.

◆ decode_switch_pos_n()

int MavlinkReceiver::decode_switch_pos_n ( uint16_t  buttons,
unsigned  sw 
)
private

Decode a switch position from a bitfield and state.

Definition at line 1784 of file mavlink_receiver.cpp.

References _mom_switch_pos, _mom_switch_state, and MOM_SWITCH_COUNT.

Referenced by handle_message_manual_control().

Here is the caller graph for this function:

◆ DEFINE_PARAMETERS()

MavlinkReceiver::DEFINE_PARAMETERS ( (ParamFloat< px4::params::BAT_CRIT_THR >)  _param_bat_crit_thr,
(ParamFloat< px4::params::BAT_EMERGEN_THR >)  _param_bat_emergen_thr,
(ParamFloat< px4::params::BAT_LOW_THR >)  _param_bat_low_thr,
(ParamInt< px4::params::COM_FLIGHT_UUID >)  _param_com_flight_uuid,
(ParamFloat< px4::params::SENS_FLOW_MAXHGT >)  _param_sens_flow_maxhgt,
(ParamFloat< px4::params::SENS_FLOW_MAXR >)  _param_sens_flow_maxr,
(ParamFloat< px4::params::SENS_FLOW_MINHGT >)  _param_sens_flow_minhgt,
(ParamInt< px4::params::SENS_FLOW_ROT >)  _param_sens_flow_rot 
)
private

◆ evaluate_target_ok()

bool MavlinkReceiver::evaluate_target_ok ( int  command,
int  target_system,
int  target_component 
)
private

Definition at line 313 of file mavlink_receiver.cpp.

References mavlink_system.

Referenced by handle_message_command_both().

Here is the caller graph for this function:

◆ fill_thrust()

void MavlinkReceiver::fill_thrust ( float *  thrust_body_array,
uint8_t  vehicle_type,
float  thrust 
)
private

Definition at line 1311 of file mavlink_receiver.cpp.

References _mavlink, Mavlink::get_system_type(), and VEHICLE_TYPE_FIXED_WING.

Referenced by handle_message_set_attitude_target().

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

◆ get_message_interval()

void MavlinkReceiver::get_message_interval ( int  msgId)
private

Definition at line 2014 of file mavlink_receiver.cpp.

References _mavlink, Mavlink::get_channel(), and Mavlink::get_streams().

Referenced by handle_message_command_both().

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

◆ handle_message()

void MavlinkReceiver::handle_message ( mavlink_message_t *  msg)
private

Definition at line 106 of file mavlink_receiver.cpp.

References _mavlink, Mavlink::get_hil_enabled(), Mavlink::get_use_hil_gps(), handle_message_adsb_vehicle(), handle_message_att_pos_mocap(), handle_message_battery_status(), handle_message_cellular_status(), handle_message_collision(), handle_message_command_ack(), handle_message_command_int(), handle_message_command_long(), handle_message_debug(), handle_message_debug_float_array(), handle_message_debug_vect(), handle_message_distance_sensor(), handle_message_follow_target(), handle_message_gps_global_origin(), handle_message_gps_rtcm_data(), handle_message_heartbeat(), handle_message_hil_gps(), handle_message_hil_optical_flow(), handle_message_hil_sensor(), handle_message_hil_state_quaternion(), handle_message_landing_target(), handle_message_logging_ack(), handle_message_manual_control(), handle_message_named_value_float(), handle_message_obstacle_distance(), handle_message_odometry(), handle_message_onboard_computer_status(), handle_message_optical_flow_rad(), handle_message_ping(), handle_message_play_tune(), handle_message_radio_status(), handle_message_rc_channels_override(), handle_message_serial_control(), handle_message_set_actuator_control_target(), handle_message_set_attitude_target(), handle_message_set_mode(), handle_message_set_position_target_global_int(), handle_message_set_position_target_local_ned(), handle_message_statustext(), handle_message_trajectory_representation_waypoints(), handle_message_utm_global_position(), handle_message_vision_position_estimate(), mavlink_system, and Mavlink::set_has_received_messages().

Referenced by Run().

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

◆ handle_message_adsb_vehicle()

void MavlinkReceiver::handle_message_adsb_vehicle ( mavlink_message_t *  msg)
private

Definition at line 2222 of file mavlink_receiver.cpp.

References _transponder_report_pub, hrt_absolute_time(), M_PI_F, uORB::PublicationQueued< T >::publish(), and transponder_report_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_att_pos_mocap()

void MavlinkReceiver::handle_message_att_pos_mocap ( mavlink_message_t *  msg)
private

Definition at line 710 of file mavlink_receiver.cpp.

References _mavlink_timesync, _mocap_odometry_pub, uORB::Publication< T >::publish(), MavlinkTimesync::sync_stamp(), and vehicle_odometry_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_battery_status()

void MavlinkReceiver::handle_message_battery_status ( mavlink_message_t *  msg)
private

Definition at line 1598 of file mavlink_receiver.cpp.

References _battery_pub, hrt_absolute_time(), mavlink_system, and uORB::Publication< T >::publish().

Referenced by handle_message().

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

◆ handle_message_cellular_status()

void MavlinkReceiver::handle_message_cellular_status ( mavlink_message_t *  msg)
private

Definition at line 2202 of file mavlink_receiver.cpp.

References _cellular_status_pub, hrt_absolute_time(), uORB::Publication< T >::publish(), status, and cellular_status_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_collision()

void MavlinkReceiver::handle_message_collision ( mavlink_message_t *  msg)
private

Definition at line 2329 of file mavlink_receiver.cpp.

References _collision_report_pub, hrt_absolute_time(), uORB::Publication< T >::publish(), and collision_report_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_command_ack()

void MavlinkReceiver::handle_message_command_ack ( mavlink_message_t *  msg)
private

Definition at line 533 of file mavlink_receiver.cpp.

References _cmd_ack_pub, _mavlink, Mavlink::get_channel(), MavlinkCommandSender::handle_mavlink_command_ack(), hrt_absolute_time(), MavlinkCommandSender::instance(), uORB::PublicationQueued< T >::publish(), and vehicle_command_ack_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_command_both()

template<class T >
void MavlinkReceiver::handle_message_command_both ( mavlink_message_t *  msg,
const T &  cmd_mavlink,
const vehicle_command_s vehicle_command 
)
private

Common method to handle both mavlink command types.

T is one of mavlink_command_int_t or mavlink_command_long_t.

Definition at line 452 of file mavlink_receiver.cpp.

References _cmd_pub, _mavlink, acknowledge(), Mavlink::configure_stream_threadsafe(), evaluate_target_ok(), f(), Mavlink::get_data_rate(), get_message_interval(), mavlink_system, uORB::PublicationQueued< T >::publish(), Mavlink::request_stop_ulog_streaming(), Mavlink::send_autopilot_capabilites(), send_flight_information(), Mavlink::send_protocol_version(), Mavlink::send_statustext_critical(), send_storage_information(), set_message_interval(), and Mavlink::try_start_ulog_streaming().

Referenced by handle_message_command_int(), and handle_message_command_long().

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

◆ handle_message_command_int()

void MavlinkReceiver::handle_message_command_int ( mavlink_message_t *  msg)
private

Definition at line 423 of file mavlink_receiver.cpp.

References handle_message_command_both(), hrt_absolute_time(), and vehicle_command_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_command_long()

void MavlinkReceiver::handle_message_command_long ( mavlink_message_t *  msg)
private

Definition at line 393 of file mavlink_receiver.cpp.

References handle_message_command_both(), hrt_absolute_time(), and vehicle_command_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_debug()

void MavlinkReceiver::handle_message_debug ( mavlink_message_t *  msg)
private

Definition at line 2522 of file mavlink_receiver.cpp.

References _debug_value_pub, hrt_absolute_time(), uORB::Publication< T >::publish(), and debug_value_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_debug_float_array()

void MavlinkReceiver::handle_message_debug_float_array ( mavlink_message_t *  msg)
private

Definition at line 2555 of file mavlink_receiver.cpp.

References _debug_array_pub, hrt_absolute_time(), uORB::Publication< T >::publish(), and debug_array_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_debug_vect()

void MavlinkReceiver::handle_message_debug_vect ( mavlink_message_t *  msg)
private

Definition at line 2537 of file mavlink_receiver.cpp.

References _debug_vect_pub, hrt_absolute_time(), uORB::Publication< T >::publish(), and debug_vect_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_distance_sensor()

void MavlinkReceiver::handle_message_distance_sensor ( mavlink_message_t *  msg)
private

Definition at line 683 of file mavlink_receiver.cpp.

References _distance_sensor_pub, f(), hrt_absolute_time(), uORB::PublicationMulti< T >::publish(), and distance_sensor_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_follow_target()

void MavlinkReceiver::handle_message_follow_target ( mavlink_message_t *  msg)
private

Definition at line 2167 of file mavlink_receiver.cpp.

References _follow_target_pub, hrt_absolute_time(), uORB::Publication< T >::publish(), and follow_target_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_gps_global_origin()

void MavlinkReceiver::handle_message_gps_global_origin ( mavlink_message_t *  msg)
private

Definition at line 1173 of file mavlink_receiver.cpp.

References _global_ref_timestamp, f(), globallocalconverter_init(), globallocalconverter_initialized(), and hrt_absolute_time().

Referenced by handle_message().

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

◆ handle_message_gps_rtcm_data()

void MavlinkReceiver::handle_message_gps_rtcm_data ( mavlink_message_t *  msg)
private

Definition at line 2349 of file mavlink_receiver.cpp.

References _gps_inject_data_pub, gps_inject_data_s::len, math::min(), and uORB::PublicationQueued< T >::publish().

Referenced by handle_message().

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

◆ handle_message_heartbeat()

void MavlinkReceiver::handle_message_heartbeat ( mavlink_message_t *  msg)
private

Definition at line 1946 of file mavlink_receiver.cpp.

References _mavlink, Mavlink::get_channel(), Mavlink::get_telemetry_status(), telemetry_status_s::heartbeat_time, hrt_absolute_time(), mavlink_system, ORB_MULTI_MAX_INSTANCES, telemetry_status_s::remote_component_id, telemetry_status_s::remote_system_id, telemetry_status_s::remote_system_status, and telemetry_status_s::remote_type.

Referenced by handle_message().

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

◆ handle_message_hil_gps()

◆ handle_message_hil_optical_flow()

void MavlinkReceiver::handle_message_hil_optical_flow ( mavlink_message_t *  msg)
private

Definition at line 615 of file mavlink_receiver.cpp.

References _flow_distance_sensor_pub, _flow_pub, f(), hrt_absolute_time(), uORB::Publication< T >::publish(), uORB::PublicationMulti< T >::publish(), and distance_sensor_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_hil_sensor()

void MavlinkReceiver::handle_message_hil_sensor ( mavlink_message_t *  msg)
private

Definition at line 2030 of file mavlink_receiver.cpp.

References _accel_pub, _airspeed_pub, _baro_pub, _battery_pub, _gyro_pub, _mag_pub, calc_EAS_from_IAS(), calc_IAS(), calc_TAS_from_EAS(), CONSTANTS_ONE_G, hrt_absolute_time(), uORB::Publication< T >::publish(), uORB::PublicationMulti< T >::publish(), sensor_accel_s::timestamp, sensor_mag_s::timestamp, sensor_baro_s::timestamp, sensor_gyro_s::timestamp, and battery_status_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_hil_state_quaternion()

◆ handle_message_landing_target()

void MavlinkReceiver::handle_message_landing_target ( mavlink_message_t *  msg)
private

Definition at line 2183 of file mavlink_receiver.cpp.

References _landing_target_pose_pub, _mavlink_timesync, uORB::Publication< T >::publish(), MavlinkTimesync::sync_stamp(), and landing_target_pose_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_logging_ack()

void MavlinkReceiver::handle_message_logging_ack ( mavlink_message_t *  msg)
private

Definition at line 1672 of file mavlink_receiver.cpp.

References _mavlink, Mavlink::get_ulog_streaming(), and MavlinkULog::handle_ack().

Referenced by handle_message().

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

◆ handle_message_manual_control()

void MavlinkReceiver::handle_message_manual_control ( mavlink_message_t *  msg)
private

Definition at line 1884 of file mavlink_receiver.cpp.

References _manual_pub, _mavlink, _mom_switch_state, _rc_pub, math::constrain(), decode_switch_pos_n(), Mavlink::get_instance_id(), Mavlink::get_manual_input_mode_generation(), Mavlink::get_system_id(), hrt_absolute_time(), uORB::PublicationMulti< T >::publish(), RC_INPUT_RSSI_MAX, input_rc_s::timestamp, and manual_control_setpoint_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_named_value_float()

void MavlinkReceiver::handle_message_named_value_float ( mavlink_message_t *  msg)
private

Definition at line 2506 of file mavlink_receiver.cpp.

References _debug_key_value_pub, hrt_absolute_time(), uORB::Publication< T >::publish(), and debug_key_value_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_obstacle_distance()

void MavlinkReceiver::handle_message_obstacle_distance ( mavlink_message_t *  msg)
private

Definition at line 1709 of file mavlink_receiver.cpp.

References _obstacle_distance_pub, hrt_absolute_time(), uORB::Publication< T >::publish(), and obstacle_distance_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_odometry()

void MavlinkReceiver::handle_message_odometry ( mavlink_message_t *  msg)
private

Definition at line 1228 of file mavlink_receiver.cpp.

References _mavlink_timesync, _mocap_odometry_pub, _visual_odometry_pub, matrix::Matrix< Type, M, N >::copyTo(), matrix::Vector< Type, M >::normalize(), uORB::Publication< T >::publish(), MavlinkTimesync::sync_stamp(), and vehicle_odometry_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_onboard_computer_status()

void MavlinkReceiver::handle_message_onboard_computer_status ( mavlink_message_t *  msg)
private

Definition at line 2575 of file mavlink_receiver.cpp.

References _onboard_computer_status_pub, hrt_absolute_time(), uORB::Publication< T >::publish(), and onboard_computer_status_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_optical_flow_rad()

void MavlinkReceiver::handle_message_optical_flow_rad ( mavlink_message_t *  msg)
private

Definition at line 562 of file mavlink_receiver.cpp.

References _flow_distance_sensor_pub, _flow_pub, f(), hrt_absolute_time(), uORB::Publication< T >::publish(), uORB::PublicationMulti< T >::publish(), rotate_3f(), and distance_sensor_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_ping()

void MavlinkReceiver::handle_message_ping ( mavlink_message_t *  msg)
private

Definition at line 1533 of file mavlink_receiver.cpp.

References _mavlink, _ping_pub, Mavlink::ping_statistics_s::dropped_packets, f(), Mavlink::get_channel(), Mavlink::get_ping_statistics(), hrt_absolute_time(), hrt_abstime, Mavlink::ping_statistics_s::last_ping_seq, Mavlink::ping_statistics_s::last_ping_time, Mavlink::ping_statistics_s::last_rtt, mavlink_system, Mavlink::ping_statistics_s::max_rtt, Mavlink::ping_statistics_s::mean_rtt, Mavlink::ping_statistics_s::min_rtt, ORB_MULTI_MAX_INSTANCES, uORB::PublicationMulti< T >::publish(), and ping_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_play_tune()

void MavlinkReceiver::handle_message_play_tune ( mavlink_message_t *  msg)
private

Definition at line 1685 of file mavlink_receiver.cpp.

References fd, mavlink_system, px4_close(), px4_open(), px4_write(), and TONE_ALARM0_DEVICE_PATH.

Referenced by handle_message().

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

◆ handle_message_radio_status()

void MavlinkReceiver::handle_message_radio_status ( mavlink_message_t *  msg)
private

Definition at line 1508 of file mavlink_receiver.cpp.

References _mavlink, _radio_status_pub, Mavlink::get_channel(), hrt_absolute_time(), ORB_MULTI_MAX_INSTANCES, uORB::PublicationMulti< T >::publish(), status, vehicle_status_s::timestamp, and Mavlink::update_radio_status().

Referenced by handle_message().

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

◆ handle_message_rc_channels_override()

void MavlinkReceiver::handle_message_rc_channels_override ( mavlink_message_t *  msg)
private

Definition at line 1819 of file mavlink_receiver.cpp.

References _mavlink, _rc_pub, Mavlink::get_system_id(), hrt_absolute_time(), uORB::PublicationMulti< T >::publish(), RC_INPUT_RSSI_MAX, and input_rc_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_serial_control()

void MavlinkReceiver::handle_message_serial_control ( mavlink_message_t *  msg)
private

Definition at line 1645 of file mavlink_receiver.cpp.

References _mavlink, Mavlink::close_shell(), Mavlink::get_shell(), and MavlinkShell::write().

Referenced by handle_message().

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

◆ handle_message_set_actuator_control_target()

void MavlinkReceiver::handle_message_set_actuator_control_target ( mavlink_message_t *  msg)
private

Definition at line 1088 of file mavlink_receiver.cpp.

References _actuator_controls_pubs, _control_mode_sub, _offboard_control_mode_pub, actuator_controls, uORB::Subscription::copy(), hrt_absolute_time(), offboard_control_mode_s::ignore_thrust, mavlink_system, and uORB::Publication< T >::publish().

Referenced by handle_message().

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

◆ handle_message_set_attitude_target()

◆ handle_message_set_mode()

void MavlinkReceiver::handle_message_set_mode ( mavlink_message_t *  msg)
private

Definition at line 654 of file mavlink_receiver.cpp.

References _cmd_pub, px4_custom_mode::data, hrt_absolute_time(), px4_custom_mode::main_mode, uORB::PublicationQueued< T >::publish(), px4_custom_mode::sub_mode, and vehicle_command_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_set_position_target_global_int()

void MavlinkReceiver::handle_message_set_position_target_global_int ( mavlink_message_t *  msg)
private

Definition at line 911 of file mavlink_receiver.cpp.

References _control_mode_sub, _mavlink, _offboard_control_mode_pub, _pos_sp_triplet_pub, _vehicle_local_position_sub, uORB::Subscription::copy(), Mavlink::get_forward_externalsp(), globallocalconverter_init(), globallocalconverter_initialized(), globallocalconverter_tolocal(), hrt_absolute_time(), offboard_control_mode_s::ignore_position, mavlink_system, uORB::Publication< T >::publish(), and position_setpoint_triplet_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_set_position_target_local_ned()

void MavlinkReceiver::handle_message_set_position_target_local_ned ( mavlink_message_t *  msg)
private

Definition at line 746 of file mavlink_receiver.cpp.

References _control_mode_sub, _mavlink, _offboard_control_mode_pub, _pos_sp_triplet_pub, uORB::Subscription::copy(), Mavlink::get_forward_externalsp(), hrt_absolute_time(), offboard_control_mode_s::ignore_position, mavlink_system, uORB::Publication< T >::publish(), and position_setpoint_triplet_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_statustext()

void MavlinkReceiver::handle_message_statustext ( mavlink_message_t *  msg)
private

Definition at line 2609 of file mavlink_receiver.cpp.

References _log_message_pub, hrt_absolute_time(), mavlink_system, uORB::Publication< T >::publish(), log_message_s::severity, and STRINGIFY.

Referenced by handle_message().

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

◆ handle_message_trajectory_representation_waypoints()

void MavlinkReceiver::handle_message_trajectory_representation_waypoints ( mavlink_message_t *  msg)
private

Definition at line 1736 of file mavlink_receiver.cpp.

References _trajectory_waypoint_pub, hrt_absolute_time(), uORB::Publication< T >::publish(), and vehicle_trajectory_waypoint_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_utm_global_position()

void MavlinkReceiver::handle_message_utm_global_position ( mavlink_message_t *  msg)
private

Definition at line 2264 of file mavlink_receiver.cpp.

References _last_utm_global_pos_com, _transponder_report_pub, hrt_absolute_time(), uORB::PublicationQueued< T >::publish(), and transponder_report_s::timestamp.

Referenced by handle_message().

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

◆ handle_message_vision_position_estimate()

void MavlinkReceiver::handle_message_vision_position_estimate ( mavlink_message_t *  msg)
private

Definition at line 1188 of file mavlink_receiver.cpp.

References _mavlink_timesync, _visual_odometry_pub, matrix::Matrix< Type, M, N >::copyTo(), uORB::Publication< T >::publish(), MavlinkTimesync::sync_stamp(), and vehicle_odometry_s::timestamp.

Referenced by handle_message().

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

◆ operator=()

MavlinkReceiver MavlinkReceiver::operator= ( const MavlinkReceiver )
privatedelete

◆ receive_start()

void MavlinkReceiver::receive_start ( pthread_t *  thread,
Mavlink parent 
)
static

Start the receiver thread.

Definition at line 2827 of file mavlink_receiver.cpp.

References MAVLINK_RECEIVER_NET_ADDED_STACK, and start_helper().

Referenced by Mavlink::task_main().

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

◆ Run()

void MavlinkReceiver::Run ( )
private

◆ send_flight_information()

void MavlinkReceiver::send_flight_information ( )
private

Definition at line 336 of file mavlink_receiver.cpp.

References _actuator_armed_sub, _mavlink, uORB::Subscription::copy(), Mavlink::get_channel(), and hrt_absolute_time().

Referenced by handle_message_command_both().

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

◆ send_storage_information()

void MavlinkReceiver::send_storage_information ( int  storage_id)
private

Definition at line 353 of file mavlink_receiver.cpp.

References _mavlink, Mavlink::get_channel(), and hrt_absolute_time().

Referenced by handle_message_command_both().

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

◆ set_message_interval()

int MavlinkReceiver::set_message_interval ( int  msgId,
float  interval,
int  data_rate = -1 
)
private

Set the interval at which the given message stream is published.

The rate is the number of messages per second.

Parameters
msgIdThe ID of the message interval to be set.
intervalThe interval in usec to send the message.
data_rateThe total link data rate in bytes per second.
Returns
PX4_OK on success, PX4_ERROR on fail.

Definition at line 1973 of file mavlink_receiver.cpp.

References _mavlink, Mavlink::configure_stream_threadsafe(), f(), get_stream_name(), and Mavlink::set_data_rate().

Referenced by handle_message_command_both().

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

◆ start_helper()

void * MavlinkReceiver::start_helper ( void *  context)
static

Definition at line 2818 of file mavlink_receiver.cpp.

References Run().

Referenced by receive_start().

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

◆ update_params()

void MavlinkReceiver::update_params ( )
private

Updates the battery, optical flow, and flight ID subscribed parameters.

Member Data Documentation

◆ _accel_pub

uORB::PublicationMulti<sensor_accel_s> MavlinkReceiver::_accel_pub {ORB_ID(sensor_accel), ORB_PRIO_LOW}
private

◆ _actuator_armed_sub

uORB::Subscription MavlinkReceiver::_actuator_armed_sub {ORB_ID(actuator_armed)}
private

Definition at line 273 of file mavlink_receiver.h.

Referenced by send_flight_information().

◆ _actuator_controls_pubs

uORB::Publication<actuator_controls_s> MavlinkReceiver::_actuator_controls_pubs[4] {ORB_ID(actuator_controls_0), ORB_ID(actuator_controls_1), ORB_ID(actuator_controls_2), ORB_ID(actuator_controls_3)}
private

Definition at line 224 of file mavlink_receiver.h.

Referenced by handle_message_set_actuator_control_target().

◆ _airspeed_pub

uORB::Publication<airspeed_s> MavlinkReceiver::_airspeed_pub {ORB_ID(airspeed)}
private

◆ _att_sp_pub

uORB::Publication<vehicle_attitude_setpoint_s> MavlinkReceiver::_att_sp_pub {ORB_ID(vehicle_attitude_setpoint)}
private

Definition at line 242 of file mavlink_receiver.h.

Referenced by handle_message_set_attitude_target().

◆ _attitude_pub

uORB::Publication<vehicle_attitude_s> MavlinkReceiver::_attitude_pub {ORB_ID(vehicle_attitude)}
private

Definition at line 241 of file mavlink_receiver.h.

Referenced by handle_message_hil_state_quaternion().

◆ _baro_pub

uORB::PublicationMulti<sensor_baro_s> MavlinkReceiver::_baro_pub {ORB_ID(sensor_baro), ORB_PRIO_LOW}
private

Definition at line 262 of file mavlink_receiver.h.

Referenced by handle_message_hil_sensor().

◆ _battery_pub

uORB::Publication<battery_status_s> MavlinkReceiver::_battery_pub {ORB_ID(battery_status)}
private

◆ _cellular_status_pub

uORB::Publication<cellular_status_s> MavlinkReceiver::_cellular_status_pub {ORB_ID(cellular_status)}
private

Definition at line 227 of file mavlink_receiver.h.

Referenced by handle_message_cellular_status().

◆ _cmd_ack_pub

uORB::PublicationQueued<vehicle_command_ack_s> MavlinkReceiver::_cmd_ack_pub {ORB_ID(vehicle_command_ack)}
private

Definition at line 269 of file mavlink_receiver.h.

Referenced by acknowledge(), and handle_message_command_ack().

◆ _cmd_pub

uORB::PublicationQueued<vehicle_command_s> MavlinkReceiver::_cmd_pub {ORB_ID(vehicle_command)}
private

Definition at line 270 of file mavlink_receiver.h.

Referenced by handle_message_command_both(), and handle_message_set_mode().

◆ _collision_report_pub

uORB::Publication<collision_report_s> MavlinkReceiver::_collision_report_pub {ORB_ID(collision_report)}
private

Definition at line 228 of file mavlink_receiver.h.

Referenced by handle_message_collision().

◆ _control_mode_sub

◆ _debug_array_pub

uORB::Publication<debug_array_s> MavlinkReceiver::_debug_array_pub {ORB_ID(debug_array)}
private

Definition at line 229 of file mavlink_receiver.h.

Referenced by handle_message_debug_float_array().

◆ _debug_key_value_pub

uORB::Publication<debug_key_value_s> MavlinkReceiver::_debug_key_value_pub {ORB_ID(debug_key_value)}
private

Definition at line 230 of file mavlink_receiver.h.

Referenced by handle_message_named_value_float().

◆ _debug_value_pub

uORB::Publication<debug_value_s> MavlinkReceiver::_debug_value_pub {ORB_ID(debug_value)}
private

Definition at line 231 of file mavlink_receiver.h.

Referenced by handle_message_debug().

◆ _debug_vect_pub

uORB::Publication<debug_vect_s> MavlinkReceiver::_debug_vect_pub {ORB_ID(debug_vect)}
private

Definition at line 232 of file mavlink_receiver.h.

Referenced by handle_message_debug_vect().

◆ _distance_sensor_pub

uORB::PublicationMulti<distance_sensor_s> MavlinkReceiver::_distance_sensor_pub {ORB_ID(distance_sensor), ORB_PRIO_LOW}
private

Definition at line 255 of file mavlink_receiver.h.

Referenced by handle_message_distance_sensor().

◆ _flow_distance_sensor_pub

uORB::PublicationMulti<distance_sensor_s> MavlinkReceiver::_flow_distance_sensor_pub {ORB_ID(distance_sensor), ORB_PRIO_LOW}
private

◆ _flow_pub

uORB::Publication<optical_flow_s> MavlinkReceiver::_flow_pub {ORB_ID(optical_flow)}
private

◆ _follow_target_pub

uORB::Publication<follow_target_s> MavlinkReceiver::_follow_target_pub {ORB_ID(follow_target)}
private

Definition at line 233 of file mavlink_receiver.h.

Referenced by handle_message_follow_target().

◆ _fw_virtual_att_sp_pub

uORB::Publication<vehicle_attitude_setpoint_s> MavlinkReceiver::_fw_virtual_att_sp_pub {ORB_ID(fw_virtual_attitude_setpoint)}
private

Definition at line 244 of file mavlink_receiver.h.

Referenced by handle_message_set_attitude_target().

◆ _global_pos_pub

uORB::Publication<vehicle_global_position_s> MavlinkReceiver::_global_pos_pub {ORB_ID(vehicle_global_position)}
private

Definition at line 245 of file mavlink_receiver.h.

Referenced by handle_message_hil_state_quaternion().

◆ _global_ref_timestamp

uint64_t MavlinkReceiver::_global_ref_timestamp {0}
private

Definition at line 284 of file mavlink_receiver.h.

Referenced by handle_message_gps_global_origin().

◆ _gps_inject_data_pub

uORB::PublicationQueued<gps_inject_data_s> MavlinkReceiver::_gps_inject_data_pub {ORB_ID(gps_inject_data)}
private

Definition at line 267 of file mavlink_receiver.h.

Referenced by handle_message_gps_rtcm_data().

◆ _gps_pub

uORB::Publication<vehicle_gps_position_s> MavlinkReceiver::_gps_pub {ORB_ID(vehicle_gps_position)}
private

Definition at line 246 of file mavlink_receiver.h.

Referenced by handle_message_hil_gps().

◆ _gyro_pub

uORB::PublicationMulti<sensor_gyro_s> MavlinkReceiver::_gyro_pub {ORB_ID(sensor_gyro), ORB_PRIO_LOW}
private

◆ _hil_local_alt0

float MavlinkReceiver::_hil_local_alt0 {0.0f}
private

Definition at line 287 of file mavlink_receiver.h.

Referenced by handle_message_hil_state_quaternion().

◆ _hil_local_proj_inited

bool MavlinkReceiver::_hil_local_proj_inited {false}
private

Definition at line 288 of file mavlink_receiver.h.

Referenced by handle_message_hil_state_quaternion().

◆ _hil_local_proj_ref

map_projection_reference_s MavlinkReceiver::_hil_local_proj_ref {}
private

Definition at line 286 of file mavlink_receiver.h.

Referenced by handle_message_hil_state_quaternion().

◆ _land_detector_pub

uORB::Publication<vehicle_land_detected_s> MavlinkReceiver::_land_detector_pub {ORB_ID(vehicle_land_detected)}
private

Definition at line 247 of file mavlink_receiver.h.

◆ _landing_target_pose_pub

uORB::Publication<landing_target_pose_s> MavlinkReceiver::_landing_target_pose_pub {ORB_ID(landing_target_pose)}
private

Definition at line 234 of file mavlink_receiver.h.

Referenced by handle_message_landing_target().

◆ _last_utm_global_pos_com

hrt_abstime MavlinkReceiver::_last_utm_global_pos_com {0}
private

Definition at line 290 of file mavlink_receiver.h.

Referenced by handle_message_utm_global_position().

◆ _local_pos_pub

uORB::Publication<vehicle_local_position_s> MavlinkReceiver::_local_pos_pub {ORB_ID(vehicle_local_position)}
private

Definition at line 248 of file mavlink_receiver.h.

Referenced by handle_message_hil_state_quaternion().

◆ _log_message_pub

uORB::Publication<log_message_s> MavlinkReceiver::_log_message_pub {ORB_ID(log_message)}
private

Definition at line 235 of file mavlink_receiver.h.

Referenced by handle_message_statustext().

◆ _mag_pub

uORB::PublicationMulti<sensor_mag_s> MavlinkReceiver::_mag_pub {ORB_ID(sensor_mag), ORB_PRIO_LOW}
private

Definition at line 264 of file mavlink_receiver.h.

Referenced by handle_message_hil_sensor().

◆ _manual_pub

uORB::PublicationMulti<manual_control_setpoint_s> MavlinkReceiver::_manual_pub {ORB_ID(manual_control_setpoint), ORB_PRIO_LOW}
private

Definition at line 258 of file mavlink_receiver.h.

Referenced by handle_message_manual_control().

◆ _mavlink

◆ _mavlink_ftp

MavlinkFTP MavlinkReceiver::_mavlink_ftp
private

Definition at line 215 of file mavlink_receiver.h.

Referenced by Run().

◆ _mavlink_log_handler

MavlinkLogHandler MavlinkReceiver::_mavlink_log_handler
private

Definition at line 216 of file mavlink_receiver.h.

Referenced by Run().

◆ _mavlink_timesync

◆ _mc_virtual_att_sp_pub

uORB::Publication<vehicle_attitude_setpoint_s> MavlinkReceiver::_mc_virtual_att_sp_pub {ORB_ID(mc_virtual_attitude_setpoint)}
private

Definition at line 243 of file mavlink_receiver.h.

Referenced by handle_message_set_attitude_target().

◆ _mission_manager

MavlinkMissionManager MavlinkReceiver::_mission_manager
private

Definition at line 217 of file mavlink_receiver.h.

Referenced by Run().

◆ _mocap_odometry_pub

uORB::Publication<vehicle_odometry_s> MavlinkReceiver::_mocap_odometry_pub {ORB_ID(vehicle_mocap_odometry)}
private

Definition at line 249 of file mavlink_receiver.h.

Referenced by handle_message_att_pos_mocap(), and handle_message_odometry().

◆ _mom_switch_pos

uint8_t MavlinkReceiver::_mom_switch_pos[MOM_SWITCH_COUNT] {}
private

Definition at line 281 of file mavlink_receiver.h.

Referenced by decode_switch_pos_n().

◆ _mom_switch_state

uint16_t MavlinkReceiver::_mom_switch_state {0}
private

Definition at line 282 of file mavlink_receiver.h.

Referenced by decode_switch_pos_n(), and handle_message_manual_control().

◆ _obstacle_distance_pub

uORB::Publication<obstacle_distance_s> MavlinkReceiver::_obstacle_distance_pub {ORB_ID(obstacle_distance)}
private

Definition at line 236 of file mavlink_receiver.h.

Referenced by handle_message_obstacle_distance().

◆ _offboard_control_mode_pub

◆ _onboard_computer_status_pub

uORB::Publication<onboard_computer_status_s> MavlinkReceiver::_onboard_computer_status_pub {ORB_ID(onboard_computer_status)}
private

Definition at line 238 of file mavlink_receiver.h.

Referenced by handle_message_onboard_computer_status().

◆ _parameter_update_sub

uORB::Subscription MavlinkReceiver::_parameter_update_sub {ORB_ID(parameter_update)}
private

Definition at line 275 of file mavlink_receiver.h.

Referenced by Run().

◆ _parameters_manager

MavlinkParametersManager MavlinkReceiver::_parameters_manager
private

Definition at line 218 of file mavlink_receiver.h.

Referenced by Run().

◆ _ping_pub

uORB::PublicationMulti<ping_s> MavlinkReceiver::_ping_pub {ORB_ID(ping), ORB_PRIO_LOW}
private

Definition at line 259 of file mavlink_receiver.h.

Referenced by handle_message_ping().

◆ _pos_sp_triplet_pub

uORB::Publication<position_setpoint_triplet_s> MavlinkReceiver::_pos_sp_triplet_pub {ORB_ID(position_setpoint_triplet)}
private

◆ _radio_status_pub

uORB::PublicationMulti<radio_status_s> MavlinkReceiver::_radio_status_pub {ORB_ID(radio_status), ORB_PRIO_LOW}
private

Definition at line 260 of file mavlink_receiver.h.

Referenced by handle_message_radio_status().

◆ _rates_sp_pub

uORB::Publication<vehicle_rates_setpoint_s> MavlinkReceiver::_rates_sp_pub {ORB_ID(vehicle_rates_setpoint)}
private

Definition at line 251 of file mavlink_receiver.h.

Referenced by handle_message_set_attitude_target().

◆ _rc_pub

uORB::PublicationMulti<input_rc_s> MavlinkReceiver::_rc_pub {ORB_ID(input_rc), ORB_PRIO_LOW}
private

◆ _status

mavlink_status_t MavlinkReceiver::_status {}
private

receiver status, used for mavlink_parse_char()

Definition at line 221 of file mavlink_receiver.h.

Referenced by Run().

◆ _trajectory_waypoint_pub

uORB::Publication<vehicle_trajectory_waypoint_s> MavlinkReceiver::_trajectory_waypoint_pub {ORB_ID(vehicle_trajectory_waypoint)}
private

◆ _transponder_report_pub

uORB::PublicationQueued<transponder_report_s> MavlinkReceiver::_transponder_report_pub {ORB_ID(transponder_report)}
private

◆ _vehicle_attitude_sub

uORB::Subscription MavlinkReceiver::_vehicle_attitude_sub {ORB_ID(vehicle_attitude)}
private

Definition at line 276 of file mavlink_receiver.h.

◆ _vehicle_local_position_sub

uORB::Subscription MavlinkReceiver::_vehicle_local_position_sub {ORB_ID(vehicle_local_position)}
private

Definition at line 277 of file mavlink_receiver.h.

Referenced by handle_message_set_position_target_global_int().

◆ _vehicle_status_sub

uORB::Subscription MavlinkReceiver::_vehicle_status_sub {ORB_ID(vehicle_status)}
private

Definition at line 278 of file mavlink_receiver.h.

Referenced by handle_message_set_attitude_target().

◆ _visual_odometry_pub

uORB::Publication<vehicle_odometry_s> MavlinkReceiver::_visual_odometry_pub {ORB_ID(vehicle_visual_odometry)}
private

◆ MOM_SWITCH_COUNT

constexpr unsigned int MavlinkReceiver::MOM_SWITCH_COUNT {8}
staticprivate

Definition at line 280 of file mavlink_receiver.h.

Referenced by decode_switch_pos_n().


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