APM:Libraries
|
MAVLink transport control class. More...
#include <GCS.h>
Classes | |
struct | pending_param_reply |
struct | pending_param_request |
struct | stream_entries |
Public Types | |
enum | streams : uint8_t { STREAM_RAW_SENSORS, STREAM_EXTENDED_STATUS, STREAM_RC_CHANNELS, STREAM_RAW_CONTROLLER, STREAM_POSITION, STREAM_EXTRA1, STREAM_EXTRA2, STREAM_EXTRA3, STREAM_PARAMS, STREAM_ADSB, NUM_STREAMS } |
Public Member Functions | |
GCS_MAVLINK () | |
void | update (uint32_t max_time_us=1000) |
void | init (AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan) |
void | setup_uart (const AP_SerialManager &serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance) |
void | send_message (enum ap_message id) |
void | send_text (MAV_SEVERITY severity, const char *fmt,...) |
void | data_stream_send () |
void | queued_param_send () |
Send the next pending parameter, called from deferred message handling code. More... | |
void | queued_waypoint_send () |
Send the next pending waypoint, called from deferred message handling code. More... | |
virtual void | packetReceived (const mavlink_status_t &status, mavlink_message_t &msg) |
AP_HAL::UARTDriver * | get_uart () |
virtual uint8_t | sysid_my_gcs () const =0 |
bool | stream_trigger (enum streams stream_num) |
bool | is_high_bandwidth () |
bool | have_flow_control () |
mavlink_channel_t | get_chan () const |
uint32_t | get_last_heartbeat_time () const |
void | send_heartbeat (void) const |
void | send_meminfo (void) |
void | send_power_status (void) |
void | send_battery_status (const AP_BattMonitor &battery, const uint8_t instance) const |
bool | send_battery_status () const |
bool | send_distance_sensor () const |
void | send_rangefinder_downward () const |
bool | send_proximity () const |
void | send_ahrs2 () |
void | send_system_time () |
void | send_radio_in () |
void | send_raw_imu () |
virtual void | send_scaled_pressure3 () |
void | send_scaled_pressure () |
void | send_sensor_offsets () |
virtual void | send_simstate () const |
void | send_ahrs () |
void | send_battery2 () |
virtual void | send_attitude () const |
void | send_autopilot_version () const |
void | send_local_position () const |
void | send_vfr_hud () |
void | send_vibration () const |
void | send_named_float (const char *name, float value) const |
void | send_home () const |
void | send_ekf_origin () const |
virtual void | send_position_target_global_int () |
void | send_servo_output_raw () |
void | send_accelcal_vehicle_position (uint32_t position) |
void | send_queued_parameters (void) |
void | retry_deferred () |
FUNCTOR_TYPEDEF (protocol_handler_fn_t, bool, uint8_t, AP_HAL::UARTDriver *) | |
Static Public Member Functions | |
static void | send_collision_all (const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour) |
static uint8_t | active_channel_mask (void) |
static uint8_t | streaming_channel_mask (void) |
static void | send_to_components (const mavlink_message_t *msg) |
static void | disable_channel_routing (mavlink_channel_t chan) |
static bool | find_by_mavtype (uint8_t mav_type, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel) |
static void | update_signing_timestamp (uint64_t timestamp_usec) |
static uint8_t | packet_overhead_chan (mavlink_channel_t chan) |
Public Attributes | |
bool | initialised |
uint32_t | last_heartbeat_time |
uint16_t | mission_item_reached_index = AP_MISSION_CMD_INDEX_NONE |
int64_t | sent_ts1 |
uint32_t | last_sent_ms |
const uint16_t | interval_ms = 10000 |
GCS_MAVLINK::protocol_handler_fn_t | handler |
uint32_t | last_mavlink_ms |
uint32_t | last_alternate_ms |
bool | active |
int64_t | link_offset_usec |
uint32_t | min_sample_counter |
int64_t | min_sample_us |
Static Public Attributes | |
static const struct AP_Param::GroupInfo | var_info [] |
static uint32_t | last_radio_status_remrssi_ms |
static const struct stream_entries | all_stream_entries [] |
Protected Member Functions | |
virtual bool | in_hil_mode () const |
virtual bool | accept_packet (const mavlink_status_t &status, mavlink_message_t &msg) |
virtual AP_Mission * | get_mission ()=0 |
virtual AP_Rally * | get_rally () const =0 |
virtual Compass * | get_compass () const =0 |
virtual class AP_Camera * | get_camera () const =0 |
virtual AP_AdvancedFailsafe * | get_advanced_failsafe () const |
virtual AP_VisualOdom * | get_visual_odom () const |
virtual bool | set_mode (uint8_t mode)=0 |
virtual const AP_FWVersion & | get_fwver () const =0 |
void | set_ekf_origin (const Location &loc) |
virtual MAV_TYPE | frame_type () const =0 |
virtual MAV_MODE | base_mode () const =0 |
virtual uint32_t | custom_mode () const =0 |
virtual MAV_STATE | system_status () const =0 |
uint8_t | packet_overhead (void) const |
virtual bool | persist_streamrates () const |
void | handle_request_data_stream (mavlink_message_t *msg) |
virtual void | handle_command_ack (const mavlink_message_t *msg) |
void | handle_set_mode (mavlink_message_t *msg) |
void | handle_mission_request_list (AP_Mission &mission, mavlink_message_t *msg) |
void | handle_mission_request (AP_Mission &mission, mavlink_message_t *msg) |
void | handle_mission_clear_all (AP_Mission &mission, mavlink_message_t *msg) |
virtual void | handle_mission_set_current (AP_Mission &mission, mavlink_message_t *msg) |
void | handle_mission_count (AP_Mission &mission, mavlink_message_t *msg) |
void | handle_mission_write_partial_list (AP_Mission &mission, mavlink_message_t *msg) |
bool | handle_mission_item (mavlink_message_t *msg, AP_Mission &mission) |
void | handle_common_param_message (mavlink_message_t *msg) |
void | handle_param_set (mavlink_message_t *msg) |
void | handle_param_request_list (mavlink_message_t *msg) |
void | handle_param_request_read (mavlink_message_t *msg) |
virtual bool | params_ready () const |
void | handle_common_gps_message (mavlink_message_t *msg) |
void | handle_common_rally_message (mavlink_message_t *msg) |
void | handle_rally_fetch_point (mavlink_message_t *msg) |
void | handle_rally_point (mavlink_message_t *msg) |
void | handle_common_camera_message (const mavlink_message_t *msg) |
void | handle_gimbal_report (AP_Mount &mount, mavlink_message_t *msg) const |
void | handle_radio_status (mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio) |
void | handle_serial_control (const mavlink_message_t *msg) |
void | handle_vision_position_delta (mavlink_message_t *msg) |
void | handle_common_message (mavlink_message_t *msg) |
void | handle_set_gps_global_origin (const mavlink_message_t *msg) |
void | handle_setup_signing (const mavlink_message_t *msg) |
MAV_RESULT | handle_preflight_reboot (const mavlink_command_long_t &packet, bool disable_overrides) |
MAV_RESULT | handle_rc_bind (const mavlink_command_long_t &packet) |
virtual MAV_RESULT | handle_flight_termination (const mavlink_command_long_t &packet) |
void | handle_send_autopilot_version (const mavlink_message_t *msg) |
MAV_RESULT | handle_command_request_autopilot_capabilities (const mavlink_command_long_t &packet) |
virtual void | send_banner () |
void | handle_device_op_read (mavlink_message_t *msg) |
void | handle_device_op_write (mavlink_message_t *msg) |
void | send_timesync () |
uint64_t | timesync_receive_timestamp_ns () const |
uint64_t | timesync_timestamp_ns () const |
void | handle_timesync (mavlink_message_t *msg) |
void | handle_statustext (mavlink_message_t *msg) |
bool | telemetry_delayed () const |
virtual uint32_t | telem_delay () const =0 |
MAV_RESULT | handle_command_preflight_set_sensor_offsets (const mavlink_command_long_t &packet) |
virtual MAV_RESULT | handle_command_preflight_calibration (const mavlink_command_long_t &packet) |
virtual MAV_RESULT | _handle_command_preflight_calibration (const mavlink_command_long_t &packet) |
virtual MAV_RESULT | _handle_command_preflight_calibration_baro () |
MAV_RESULT | handle_command_mag_cal (const mavlink_command_long_t &packet) |
MAV_RESULT | handle_command_long_message (mavlink_command_long_t &packet) |
MAV_RESULT | handle_command_camera (const mavlink_command_long_t &packet) |
MAV_RESULT | handle_command_do_send_banner (const mavlink_command_long_t &packet) |
MAV_RESULT | handle_command_do_set_mode (const mavlink_command_long_t &packet) |
MAV_RESULT | handle_command_get_home_position (const mavlink_command_long_t &packet) |
virtual bool | try_send_message (enum ap_message id) |
bool | try_send_compass_message (enum ap_message id) |
bool | try_send_mission_message (enum ap_message id) |
bool | try_send_camera_message (enum ap_message id) |
bool | try_send_gps_message (enum ap_message id) |
void | send_hwstatus () |
void | handle_data_packet (mavlink_message_t *msg) |
virtual int32_t | global_position_int_alt () const |
virtual int32_t | global_position_int_relative_alt () const |
virtual bool | vfr_hud_make_alt_relative () const |
virtual float | vfr_hud_climbrate () const |
virtual float | vfr_hud_airspeed () const |
virtual int16_t | vfr_hud_throttle () const |
Protected Attributes | |
bool | waypoint_receiving |
uint16_t | waypoint_request_i |
uint16_t | waypoint_request_last |
AP_Param * | _queued_parameter |
next parameter to More... | |
mavlink_channel_t | chan |
AP_Int16 | streamRates [NUM_STREAMS] |
struct { | |
int64_t sent_ts1 | |
uint32_t last_sent_ms | |
const uint16_t interval_ms = 10000 | |
} | _timesync_request |
Vector3f | vfr_hud_velned |
Private Member Functions | |
float | adjust_rate_for_stream_trigger (enum streams stream_num) |
MAV_RESULT | _set_mode_common (const MAV_MODE base_mode, const uint32_t custom_mode) |
virtual void | handleMessage (mavlink_message_t *msg)=0 |
MAV_RESULT | handle_servorelay_message (mavlink_command_long_t &packet) |
bool | calibrate_gyros () |
void | param_io_timer (void) |
void | send_parameter_reply (void) |
void | send_distance_sensor (const AP_RangeFinder_Backend *sensor, const uint8_t instance) const |
virtual bool | handle_guided_request (AP_Mission::Mission_Command &cmd)=0 |
virtual void | handle_change_alt_request (AP_Mission::Mission_Command &cmd)=0 |
void | handle_common_mission_message (mavlink_message_t *msg) |
void | handle_vicon_position_estimate (mavlink_message_t *msg) |
void | handle_vision_position_estimate (mavlink_message_t *msg) |
void | handle_global_vision_position_estimate (mavlink_message_t *msg) |
void | handle_att_pos_mocap (mavlink_message_t *msg) |
void | handle_common_vision_position_estimate_data (const uint64_t usec, const float x, const float y, const float z, const float roll, const float pitch, const float yaw, const uint16_t payload_size) |
void | log_vision_position_estimate_data (const uint64_t usec, const float x, const float y, const float z, const float roll, const float pitch, const float yaw) |
void | push_deferred_messages () |
void | lock_channel (mavlink_channel_t chan, bool lock) |
uint32_t | correct_offboard_timestamp_usec_to_ms (uint64_t offboard_usec, uint16_t payload_size) |
void | load_signing_key (void) |
bool | signing_enabled (void) const |
void | send_global_position_int () |
Static Private Member Functions | |
static bool | signing_key_save (const struct SigningKey &key) |
static bool | signing_key_load (struct SigningKey &key) |
static void | save_signing_timestamp (bool force_save_now) |
Static Private Attributes | |
static uint32_t | reserve_param_space_start_ms |
static uint8_t | mavlink_active = 0 |
static uint8_t | chan_is_streaming = 0 |
static MAVLink_routing | routing |
static AP_Frsky_Telem * | frsky_telemetry_p |
static const AP_SerialManager * | serialmanager_p |
static ObjectBuffer< pending_param_request > | param_requests |
static ObjectBuffer< pending_param_reply > | param_replies |
static bool | param_timer_registered |
static mavlink_signing_streams_t | signing_streams |
static uint32_t | last_signing_save_ms |
static StorageAccess | _signing_storage |
Friends | |
class | GCS |
MAVLink transport control class.
Definition at line 98 of file AHRS_Test.cpp.
enum GCS_MAVLINK::streams : uint8_t |
GCS_MAVLINK::GCS_MAVLINK | ( | ) |
|
protectedvirtual |
Definition at line 2529 of file GCS_Common.cpp.
Referenced by handle_command_preflight_calibration().
|
protectedvirtual |
Definition at line 2514 of file GCS_Common.cpp.
Referenced by _handle_command_preflight_calibration().
|
private |
Definition at line 1411 of file GCS_Common.cpp.
Referenced by handle_command_do_set_mode(), and handle_set_mode().
|
inlineprotectedvirtual |
Definition at line 252 of file GCS.h.
Referenced by packetReceived().
|
inlinestatic |
Definition at line 201 of file GCS.h.
Referenced by MAVLink_routing::handle_heartbeat(), GCS::send_parameter_value(), AP_Button::send_report(), GCS::send_statustext(), and GCS::send_text().
|
private |
Definition at line 1637 of file GCS_Common.cpp.
Referenced by stream_trigger().
|
protectedpure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by get_visual_odom(), and send_heartbeat().
|
private |
Definition at line 2504 of file GCS_Common.cpp.
Referenced by _handle_command_preflight_calibration().
|
private |
Definition at line 3105 of file GCS_Common.cpp.
Referenced by handle_common_vision_position_estimate_data().
|
protectedpure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by get_visual_odom(), and send_heartbeat().
void GCS_MAVLINK::data_stream_send | ( | void | ) |
Definition at line 3041 of file GCS_Common.cpp.
Referenced by GCS::instance().
|
inlinestatic |
|
inlinestatic |
Definition at line 227 of file GCS.h.
Referenced by AP_Mount_SToRM32::find_gimbal().
|
protectedpure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by get_visual_odom(), and send_heartbeat().
GCS_MAVLINK::FUNCTOR_TYPEDEF | ( | protocol_handler_fn_t | , |
bool | , | ||
uint8_t | , | ||
AP_HAL::UARTDriver * | |||
) |
|
inlineprotectedvirtual |
Definition at line 257 of file GCS.h.
Referenced by handle_flight_termination().
|
protectedpure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by accept_packet(), handle_command_camera(), handle_common_camera_message(), and try_send_camera_message().
|
inline |
Definition at line 152 of file GCS.h.
Referenced by DataFlash_Class::handle_log_request_data(), DataFlash_Class::handle_log_send_data(), DataFlash_Class::handle_log_send_listing(), DataFlash_Class::handle_mavlink_msg(), AC_Fence::handle_msg(), and send_simstate().
|
protectedpure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by accept_packet(), handle_command_mag_cal(), handle_command_preflight_set_sensor_offsets(), and try_send_compass_message().
|
protectedpure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by get_visual_odom(), send_autopilot_version(), and send_banner().
|
inline |
Definition at line 153 of file GCS.h.
Referenced by DataFlash_Class::handle_log_send_data(), and DataFlash_Class::handle_log_send_listing().
|
protectedpure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by accept_packet(), handle_common_mission_message(), and try_send_mission_message().
|
protectedpure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by accept_packet(), handle_rally_fetch_point(), and handle_rally_point().
|
inline |
Definition at line 119 of file GCS.h.
Referenced by AP_AccelCal::_printf().
|
inlineprotectedvirtual |
Definition at line 258 of file GCS.h.
Referenced by handle_vision_position_delta().
|
protectedvirtual |
Definition at line 2846 of file GCS_Common.cpp.
Referenced by send_global_position_int().
|
protectedvirtual |
Definition at line 2849 of file GCS_Common.cpp.
Referenced by send_global_position_int().
|
private |
Definition at line 2190 of file GCS_Common.cpp.
Referenced by handle_common_message().
|
privatepure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by handle_mission_item().
|
protectedvirtual |
Definition at line 2225 of file GCS_Common.cpp.
Referenced by handle_common_message(), and persist_streamrates().
|
protected |
Definition at line 1984 of file GCS_Common.cpp.
Referenced by handle_command_long_message().
|
protected |
Definition at line 2605 of file GCS_Common.cpp.
Referenced by handle_command_long_message().
|
protected |
Definition at line 2611 of file GCS_Common.cpp.
Referenced by handle_command_long_message().
|
protected |
Definition at line 2619 of file GCS_Common.cpp.
Referenced by handle_command_long_message().
|
protected |
|
protected |
Definition at line 2584 of file GCS_Common.cpp.
Referenced by handle_command_long_message().
|
protectedvirtual |
Definition at line 2574 of file GCS_Common.cpp.
Referenced by handle_command_long_message().
|
protected |
Definition at line 2482 of file GCS_Common.cpp.
Referenced by handle_command_long_message().
|
protected |
Definition at line 2593 of file GCS_Common.cpp.
Referenced by handle_command_long_message(), and params_ready().
|
protected |
Definition at line 1965 of file GCS_Common.cpp.
Referenced by handle_common_message(), and params_ready().
|
protected |
Definition at line 1959 of file GCS_Common.cpp.
Referenced by handle_common_message(), and params_ready().
|
protected |
Definition at line 2236 of file GCS_Common.cpp.
Referenced by params_ready().
|
private |
Definition at line 2383 of file GCS_Common.cpp.
Referenced by handle_common_message().
|
protected |
Definition at line 442 of file GCS_Param.cpp.
Referenced by handle_common_message(), and persist_streamrates().
|
protected |
Definition at line 87 of file GCS_Rally.cpp.
Referenced by handle_common_message(), and params_ready().
|
private |
Definition at line 2133 of file GCS_Common.cpp.
Referenced by handle_global_vision_position_estimate(), handle_vicon_position_estimate(), and handle_vision_position_estimate().
|
protected |
Definition at line 2072 of file GCS_Common.cpp.
Referenced by handle_common_message().
|
protected |
Definition at line 29 of file GCS_DeviceOp.cpp.
Referenced by handle_common_message(), and params_ready().
|
protected |
Definition at line 81 of file GCS_DeviceOp.cpp.
Referenced by handle_common_message(), and params_ready().
|
protectedvirtual |
Definition at line 1818 of file GCS_Common.cpp.
Referenced by handle_command_long_message(), and params_ready().
|
protected |
Definition at line 599 of file GCS_Common.cpp.
Referenced by params_ready().
|
private |
Definition at line 2112 of file GCS_Common.cpp.
Referenced by handle_common_message().
|
privatepure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by handle_mission_item().
|
protected |
Definition at line 550 of file GCS_Common.cpp.
Referenced by handle_common_mission_message(), and persist_streamrates().
|
protected |
Definition at line 519 of file GCS_Common.cpp.
Referenced by handle_common_mission_message(), and persist_streamrates().
|
protected |
Definition at line 654 of file GCS_Common.cpp.
Referenced by handle_common_mission_message(), and persist_streamrates().
|
protected |
Definition at line 395 of file GCS_Common.cpp.
Referenced by handle_common_mission_message(), and persist_streamrates().
|
protected |
Definition at line 378 of file GCS_Common.cpp.
Referenced by handle_common_mission_message(), and persist_streamrates().
|
protectedvirtual |
Definition at line 504 of file GCS_Common.cpp.
Referenced by handle_common_mission_message(), and persist_streamrates().
|
protected |
Definition at line 571 of file GCS_Common.cpp.
Referenced by handle_common_mission_message(), and persist_streamrates().
|
protected |
Definition at line 188 of file GCS_Param.cpp.
Referenced by handle_common_param_message(), and persist_streamrates().
|
protected |
Definition at line 206 of file GCS_Param.cpp.
Referenced by handle_common_param_message(), and persist_streamrates().
|
protected |
Definition at line 238 of file GCS_Param.cpp.
Referenced by handle_common_param_message(), and persist_streamrates().
|
protected |
Definition at line 1781 of file GCS_Common.cpp.
Referenced by params_ready().
|
protected |
Definition at line 616 of file GCS_Common.cpp.
Referenced by params_ready().
|
protected |
Definition at line 59 of file GCS_Rally.cpp.
Referenced by handle_common_rally_message(), and params_ready().
|
protected |
Definition at line 20 of file GCS_Rally.cpp.
Referenced by handle_common_rally_message(), and params_ready().
|
protected |
Definition at line 1836 of file GCS_Common.cpp.
Referenced by handle_command_long_message(), and params_ready().
|
protected |
Definition at line 127 of file GCS_Param.cpp.
Referenced by handle_common_message(), and persist_streamrates().
|
protected |
Definition at line 2447 of file GCS_Common.cpp.
Referenced by handle_common_message(), and params_ready().
|
protected |
handle a SERIAL_CONTROL message
Definition at line 30 of file GCS_serial_control.cpp.
Referenced by handle_common_message(), and params_ready().
|
private |
Definition at line 5 of file GCS_ServoRelay.cpp.
Referenced by handle_command_long_message().
|
protected |
Definition at line 2051 of file GCS_Common.cpp.
Referenced by handle_common_message(), and params_ready().
|
protected |
Definition at line 1394 of file GCS_Common.cpp.
Referenced by handle_common_message(), and persist_streamrates().
|
protected |
Definition at line 66 of file GCS_Signing.cpp.
Referenced by handle_common_message(), and params_ready().
|
protected |
Definition at line 1931 of file GCS_Common.cpp.
Referenced by handle_common_message().
|
protected |
Definition at line 1867 of file GCS_Common.cpp.
Referenced by handle_common_message(), and params_ready().
|
private |
Definition at line 2121 of file GCS_Common.cpp.
Referenced by handle_common_message().
|
protected |
Definition at line 2094 of file GCS_Common.cpp.
Referenced by handle_common_message(), and params_ready().
|
private |
Definition at line 2103 of file GCS_Common.cpp.
Referenced by handle_common_message().
|
privatepure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by packetReceived().
bool GCS_MAVLINK::have_flow_control | ( | void | ) |
Definition at line 103 of file GCS_Param.cpp.
Referenced by DataFlash_Class::handle_log_send(), is_high_bandwidth(), and queued_param_send().
|
inlineprotectedvirtual |
Definition at line 248 of file GCS.h.
Referenced by data_stream_send(), and send_servo_output_raw().
void GCS_MAVLINK::init | ( | AP_HAL::UARTDriver * | port, |
mavlink_channel_t | mav_chan | ||
) |
Definition at line 58 of file GCS_Common.cpp.
Referenced by setup(), and setup_uart().
|
inline |
Definition at line 148 of file GCS.h.
Referenced by DataFlash_Class::handle_log_send().
|
private |
Definition at line 116 of file GCS_Signing.cpp.
Referenced by setup_uart().
|
private |
Definition at line 56 of file GCS_MAVLink.cpp.
Referenced by handle_serial_control().
|
private |
Definition at line 2170 of file GCS_Common.cpp.
Referenced by handle_att_pos_mocap(), and handle_common_vision_position_estimate_data().
|
inlineprotected |
Definition at line 276 of file GCS.h.
Referenced by queued_param_send().
|
static |
Definition at line 238 of file GCS_Signing.cpp.
Referenced by MAVLink_routing::check_and_forward(), find_by_mavtype(), MAVLink_routing::handle_heartbeat(), packet_overhead(), and MAVLink_routing::send_to_components().
|
virtual |
Definition at line 855 of file GCS_Common.cpp.
Referenced by update().
|
private |
Definition at line 375 of file GCS_Param.cpp.
Referenced by send_queued_parameters().
|
inlineprotectedvirtual |
Definition at line 298 of file GCS.h.
Referenced by handle_param_request_list().
|
inlineprotectedvirtual |
Definition at line 281 of file GCS.h.
Referenced by handle_request_data_stream().
|
private |
Definition at line 792 of file GCS_Common.cpp.
Referenced by retry_deferred(), and send_message().
void GCS_MAVLINK::queued_param_send | ( | ) |
Send the next pending parameter, called from deferred message handling code.
Definition at line 36 of file GCS_Param.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::queued_waypoint_send | ( | ) |
Send the next pending waypoint, called from deferred message handling code.
Definition at line 165 of file GCS_Common.cpp.
Referenced by handle_mission_item(), and try_send_mission_message().
void GCS_MAVLINK::retry_deferred | ( | ) |
Definition at line 806 of file GCS_Common.cpp.
Referenced by GCS::instance(), and streaming_channel_mask().
|
staticprivate |
Definition at line 193 of file GCS_Signing.cpp.
Referenced by send_message().
void GCS_MAVLINK::send_accelcal_vehicle_position | ( | uint32_t | position | ) |
Definition at line 1716 of file GCS_Common.cpp.
Referenced by send_position_target_global_int(), and AP_AccelCal::update().
void GCS_MAVLINK::send_ahrs | ( | ) |
Definition at line 1219 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_ahrs2 | ( | ) |
Definition at line 342 of file GCS_Common.cpp.
Referenced by try_send_message().
|
virtual |
Definition at line 2831 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_autopilot_version | ( | ) | const |
Definition at line 1478 of file GCS_Common.cpp.
Referenced by handle_command_request_autopilot_capabilities(), and handle_send_autopilot_version().
|
protectedvirtual |
Definition at line 2452 of file GCS_Common.cpp.
Referenced by handle_command_do_send_banner(), handle_param_request_list(), and params_ready().
void GCS_MAVLINK::send_battery2 | ( | ) |
Definition at line 1376 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_battery_status | ( | const AP_BattMonitor & | battery, |
const uint8_t | instance | ||
) | const |
bool GCS_MAVLINK::send_battery_status | ( | ) | const |
Definition at line 217 of file GCS_Common.cpp.
Referenced by try_send_message().
|
static |
Definition at line 1695 of file GCS_Common.cpp.
Referenced by AP_Avoidance::handle_threat_gcs_notify(), and send_position_target_global_int().
bool GCS_MAVLINK::send_distance_sensor | ( | ) | const |
Definition at line 246 of file GCS_Common.cpp.
Referenced by try_send_message().
|
private |
void GCS_MAVLINK::send_ekf_origin | ( | ) | const |
Definition at line 1606 of file GCS_Common.cpp.
Referenced by handle_command_get_home_position(), GCS::instance(), and set_ekf_origin().
|
private |
Definition at line 2855 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_heartbeat | ( | void | ) | const |
Definition at line 1626 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_home | ( | ) | const |
Definition at line 1583 of file GCS_Common.cpp.
Referenced by handle_command_get_home_position(), and GCS::instance().
|
protected |
Definition at line 2765 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_local_position | ( | ) | const |
Definition at line 1534 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_meminfo | ( | void | ) |
Definition at line 179 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_message | ( | enum ap_message | id | ) |
Definition at line 812 of file GCS_Common.cpp.
Referenced by data_stream_send(), handle_mission_item(), GCS::instance(), send_queued_parameters(), and update().
void GCS_MAVLINK::send_named_float | ( | const char * | name, |
float | value | ||
) | const |
Definition at line 1576 of file GCS_Common.cpp.
Referenced by GCS::instance().
|
private |
Definition at line 424 of file GCS_Param.cpp.
Referenced by queued_param_send().
|
inlinevirtual |
Definition at line 194 of file GCS.h.
Referenced by try_send_message().
void GCS_MAVLINK::send_power_status | ( | void | ) |
bool GCS_MAVLINK::send_proximity | ( | ) | const |
Definition at line 296 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_queued_parameters | ( | void | ) |
Definition at line 352 of file GCS_Param.cpp.
Referenced by data_stream_send(), and streaming_channel_mask().
void GCS_MAVLINK::send_radio_in | ( | ) |
Definition at line 988 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_rangefinder_downward | ( | ) | const |
Definition at line 280 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_raw_imu | ( | ) |
Definition at line 1047 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_scaled_pressure | ( | ) |
Definition at line 1152 of file GCS_Common.cpp.
Referenced by try_send_message().
|
virtual |
Definition at line 1132 of file GCS_Common.cpp.
Referenced by send_scaled_pressure().
void GCS_MAVLINK::send_sensor_offsets | ( | ) |
Definition at line 1185 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_servo_output_raw | ( | ) |
Definition at line 1669 of file GCS_Common.cpp.
Referenced by send_position_target_global_int(), and try_send_message().
|
virtual |
Definition at line 2471 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_system_time | ( | ) |
Definition at line 976 of file GCS_Common.cpp.
Referenced by try_send_gps_message().
void GCS_MAVLINK::send_text | ( | MAV_SEVERITY | severity, |
const char * | fmt, | ||
... | |||
) |
Definition at line 605 of file GCS_Common.cpp.
Referenced by AP_AccelCal::_printf(), handle_command_long_message(), DataFlash_Class::handle_log_request_data(), DataFlash_Class::handle_log_request_list(), handle_mission_item(), handle_mission_write_partial_list(), AC_Fence::handle_msg(), handle_rally_fetch_point(), handle_rally_point(), GCS::instance(), and send_banner().
|
protected |
Definition at line 1921 of file GCS_Common.cpp.
Referenced by params_ready(), and update().
|
inlinestatic |
Definition at line 216 of file GCS.h.
Referenced by AP_Camera::configure(), AP_Camera::control(), and AP_Camera::take_picture().
void GCS_MAVLINK::send_vfr_hud | ( | ) |
Definition at line 1748 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::send_vibration | ( | ) | const |
Definition at line 1559 of file GCS_Common.cpp.
Referenced by try_send_message().
|
protected |
Definition at line 2025 of file GCS_Common.cpp.
Referenced by get_visual_odom(), and handle_set_gps_global_origin().
|
protectedpure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by _set_mode_common(), and get_visual_odom().
void GCS_MAVLINK::setup_uart | ( | const AP_SerialManager & | serial_manager, |
AP_SerialManager::SerialProtocol | protocol, | ||
uint8_t | instance | ||
) |
|
private |
Definition at line 226 of file GCS_Signing.cpp.
|
staticprivate |
Definition at line 49 of file GCS_Signing.cpp.
|
staticprivate |
Definition at line 41 of file GCS_Signing.cpp.
bool GCS_MAVLINK::stream_trigger | ( | enum streams | stream_num | ) |
Definition at line 279 of file GCS_Param.cpp.
Referenced by data_stream_send(), and send_queued_parameters().
|
inlinestatic |
Definition at line 204 of file GCS.h.
Referenced by GCS::send_statustext(), and GCS::send_text().
|
pure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by get_uart(), and handle_statustext().
|
protectedpure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by get_visual_odom(), and send_heartbeat().
|
protectedpure virtual |
Implemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Referenced by telemetry_delayed().
|
protected |
Definition at line 1650 of file GCS_Common.cpp.
Referenced by try_send_message().
|
protected |
Definition at line 1847 of file GCS_Common.cpp.
Referenced by handle_timesync(), and params_ready().
|
protected |
Definition at line 1856 of file GCS_Common.cpp.
Referenced by params_ready(), and send_timesync().
|
protected |
Definition at line 2810 of file GCS_Common.cpp.
Referenced by try_send_message().
|
protected |
Definition at line 2711 of file GCS_Common.cpp.
Referenced by try_send_message().
|
protected |
Definition at line 2773 of file GCS_Common.cpp.
Referenced by try_send_message().
|
protectedvirtual |
Reimplemented in GCS_MAVLINK_routing, and GCS_MAVLINK_Dummy.
Definition at line 2877 of file GCS_Common.cpp.
Referenced by push_deferred_messages(), and send_message().
|
protected |
Definition at line 2734 of file GCS_Common.cpp.
Referenced by try_send_message().
void GCS_MAVLINK::update | ( | uint32_t | max_time_us = 1000 | ) |
Definition at line 882 of file GCS_Common.cpp.
Referenced by GCS::instance().
|
static |
Definition at line 164 of file GCS_Signing.cpp.
Referenced by find_by_mavtype().
|
protectedvirtual |
Definition at line 1731 of file GCS_Common.cpp.
Referenced by send_vfr_hud(), and vfr_hud_make_alt_relative().
|
protectedvirtual |
Definition at line 1743 of file GCS_Common.cpp.
Referenced by send_vfr_hud(), and vfr_hud_make_alt_relative().
|
inlineprotectedvirtual |
Definition at line 374 of file GCS.h.
Referenced by send_vfr_hud().
|
inlineprotectedvirtual |
Definition at line 377 of file GCS.h.
Referenced by send_vfr_hud().
|
private |
|
private |
|
private |
|
private |
|
private |
The stream we are communicating over.
Definition at line 393 of file GCS.h.
Referenced by correct_offboard_timestamp_usec_to_ms(), get_uart(), have_flow_control(), init(), timesync_receive_timestamp_ns(), and update().
|
protected |
next parameter to
Definition at line 273 of file GCS.h.
Referenced by adjust_rate_for_stream_trigger(), handle_param_request_list(), init(), queued_param_send(), and send_queued_parameters().
|
private |
saved count of
Definition at line 403 of file GCS.h.
Referenced by handle_param_request_list(), and queued_param_send().
|
private |
AP_Param token for.
next queued
Definition at line 401 of file GCS.h.
Referenced by handle_param_request_list(), and queued_param_send().
|
private |
Definition at line 406 of file GCS.h.
Referenced by queued_param_send().
|
private |
Definition at line 399 of file GCS.h.
Referenced by handle_param_request_list(), and queued_param_send().
|
private |
type of the next
Perform queued sending operations
Definition at line 397 of file GCS.h.
Referenced by handle_param_request_list(), and queued_param_send().
|
staticprivate |
struct { ... } GCS_MAVLINK::_timesync_request |
Referenced by handle_timesync(), send_timesync(), and update().
|
static |
Definition at line 244 of file GCS.h.
Referenced by data_stream_send().
struct { ... } GCS_MAVLINK::alternative |
Referenced by GCS::install_alternative_protocol(), and update().
|
protected |
Definition at line 275 of file GCS.h.
Referenced by _set_mode_common(), comm_get_available(), comm_get_txspace(), comm_send_buffer(), GCS::data_stream_send(), find_by_mavtype(), get_chan(), handle_data_packet(), handle_device_op_read(), handle_device_op_write(), handle_gimbal_report(), handle_global_vision_position_estimate(), handle_mission_clear_all(), handle_mission_count(), handle_mission_item(), handle_mission_request(), handle_mission_request_list(), handle_mission_set_current(), handle_param_request_read(), handle_rally_fetch_point(), handle_serial_control(), handle_set_mode(), handle_timesync(), handle_vicon_position_estimate(), handle_vision_position_estimate(), have_flow_control(), init(), GCS::instance(), is_high_bandwidth(), lock_channel(), packetReceived(), queued_param_send(), queued_waypoint_send(), GCS::retry_deferred(), send_accelcal_vehicle_position(), send_ahrs(), send_ahrs2(), send_attitude(), send_autopilot_version(), send_battery2(), send_battery_status(), send_collision_all(), send_distance_sensor(), send_ekf_origin(), send_global_position_int(), send_heartbeat(), send_home(), send_hwstatus(), send_local_position(), send_meminfo(), GCS::send_message(), GCS::send_mission_item_reached_message(), send_named_float(), send_power_status(), send_proximity(), send_radio_in(), send_rangefinder_downward(), send_raw_imu(), send_scaled_pressure(), send_scaled_pressure3(), send_sensor_offsets(), send_servo_output_raw(), send_system_time(), send_text(), send_timesync(), send_vfr_hud(), send_vibration(), setup_uart(), GCS::setup_uarts(), stream_trigger(), telemetry_delayed(), timesync_receive_timestamp_ns(), try_send_camera_message(), try_send_compass_message(), try_send_gps_message(), try_send_mission_message(), update(), and GCS::update().
|
staticprivate |
Definition at line 453 of file GCS.h.
Referenced by stream_trigger(), and streaming_channel_mask().
|
private |
Definition at line 442 of file GCS.h.
Referenced by push_deferred_messages(), and send_message().
|
staticprivate |
Definition at line 459 of file GCS.h.
Referenced by GCS::register_frsky_telemetry_callback(), and GCS::send_statustext().
|
private |
Definition at line 555 of file GCS.h.
Referenced by global_position_int_alt(), send_global_position_int(), and send_vfr_hud().
GCS_MAVLINK::protocol_handler_fn_t GCS_MAVLINK::handler |
Definition at line 539 of file GCS.h.
Referenced by handle_servorelay_message(), and GCS::install_alternative_protocol().
bool GCS_MAVLINK::initialised |
Definition at line 126 of file GCS.h.
Referenced by init(), queued_param_send(), and queued_waypoint_send().
struct { ... } GCS_MAVLINK::lag_correction |
Referenced by correct_offboard_timestamp_usec_to_ms().
uint32_t GCS_MAVLINK::last_heartbeat_time |
Definition at line 153 of file GCS.h.
Referenced by try_send_message().
|
static |
Definition at line 158 of file GCS.h.
Referenced by handle_radio_status().
|
staticprivate |
Definition at line 450 of file GCS.h.
Referenced by active_channel_mask(), packetReceived(), send_collision_all(), and GCS::send_parameter_value().
uint16_t GCS_MAVLINK::mission_item_reached_index = AP_MISSION_CMD_INDEX_NONE |
Definition at line 161 of file GCS.h.
Referenced by try_send_mission_message().
|
private |
Definition at line 443 of file GCS.h.
Referenced by push_deferred_messages(), and send_message().
|
private |
Definition at line 444 of file GCS.h.
Referenced by push_deferred_messages(), and send_message().
|
private |
|
staticprivate |
Definition at line 480 of file GCS.h.
Referenced by param_io_timer(), send_parameter_reply(), and send_queued_parameters().
|
staticprivate |
Definition at line 479 of file GCS.h.
Referenced by handle_param_request_read(), and param_io_timer().
|
staticprivate |
Definition at line 483 of file GCS.h.
Referenced by send_queued_parameters().
|
staticprivate |
Definition at line 447 of file GCS.h.
Referenced by handle_param_request_read().
|
staticprivate |
Definition at line 456 of file GCS.h.
Referenced by disable_channel_routing(), find_by_mavtype(), packetReceived(), and send_to_components().
|
staticprivate |
Definition at line 461 of file GCS.h.
Referenced by packetReceived(), and setup_uart().
|
staticprivate |
|
private |
Definition at line 432 of file GCS.h.
Referenced by handle_radio_status(), stream_trigger(), and update().
|
private |
Definition at line 429 of file GCS.h.
Referenced by stream_trigger().
|
protected |
Definition at line 279 of file GCS.h.
Referenced by handle_request_data_stream(), send_queued_parameters(), and stream_trigger().
|
static |
|
protected |
Definition at line 378 of file GCS.h.
Referenced by send_vfr_hud(), and vfr_hud_climbrate().
|
private |
Definition at line 422 of file GCS.h.
Referenced by handle_mission_count(), handle_mission_write_partial_list(), and queued_waypoint_send().
|
private |
Definition at line 421 of file GCS.h.
Referenced by handle_mission_count(), handle_mission_write_partial_list(), and queued_waypoint_send().
|
private |
|
protected |
Definition at line 268 of file GCS.h.
Referenced by adjust_rate_for_stream_trigger(), data_stream_send(), handle_mission_count(), handle_mission_item(), handle_mission_request_list(), handle_mission_write_partial_list(), queued_waypoint_send(), and update().
|
protected |
Definition at line 270 of file GCS.h.
Referenced by handle_mission_count(), handle_mission_item(), handle_mission_write_partial_list(), and queued_waypoint_send().
|
protected |
Definition at line 271 of file GCS.h.
Referenced by handle_mission_count(), handle_mission_item(), handle_mission_write_partial_list(), and queued_waypoint_send().
|
private |
Definition at line 424 of file GCS.h.
Referenced by handle_mission_count(), handle_mission_item(), handle_mission_write_partial_list(), and update().
|
private |
Definition at line 425 of file GCS.h.
Referenced by handle_mission_count(), handle_mission_item(), handle_mission_write_partial_list(), and update().