27 #define PAYLOAD_SIZE(chan, id) (GCS_MAVLINK::packet_overhead_chan(chan)+MAVLINK_MSG_ID_ ## id ## _LEN) 28 #define HAVE_PAYLOAD_SPACE(chan, id) (comm_get_txspace(chan) >= PAYLOAD_SIZE(chan, id)) 29 #define CHECK_PAYLOAD_SIZE(id) if (comm_get_txspace(chan) < packet_overhead()+MAVLINK_MSG_ID_ ## id ## _LEN) return false 30 #define CHECK_PAYLOAD_SIZE2(id) if (!HAVE_PAYLOAD_SPACE(chan, id)) return false 89 #define MAV_STREAM_ENTRY(stream_name) \ 91 GCS_MAVLINK::stream_name, \ 92 stream_name ## _msgs, \ 93 ARRAY_SIZE(stream_name ## _msgs) \ 95 #define MAV_STREAM_TERMINATOR { (streams)0, nullptr, 0 } 106 void update(uint32_t max_time_us=1000);
110 void send_text(MAV_SEVERITY severity,
const char *
fmt, ...);
116 mavlink_message_t &msg);
168 const uint8_t instance)
const;
183 #if AP_AHRS_NAVEKF_AVAILABLE 252 virtual bool accept_packet(
const mavlink_status_t &status, mavlink_message_t &msg) {
return true; }
259 virtual bool set_mode(uint8_t mode) = 0;
508 const uint16_t payload_size);
568 if (_singleton ==
nullptr) {
571 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 583 void send_text(MAV_SEVERITY severity,
const char *
fmt, ...);
584 virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask,
const char *text);
588 virtual uint8_t
num_gcs()
const = 0;
646 #if HAL_CPU_CLASS <= HAL_CPU_CLASS_150 || CONFIG_HAL_BOARD == HAL_BOARD_SITL 647 static const uint8_t _status_capacity = 5;
649 static const uint8_t _status_capacity = 30;
uint16_t waypoint_dest_compid
AP_Param::ParamToken _queued_parameter_token
void handle_param_set(mavlink_message_t *msg)
void handle_device_op_read(mavlink_message_t *msg)
virtual void send_banner()
uint16_t _queued_parameter_index
AP_Param token for.
static void send_to_components(const mavlink_message_t *msg)
void set_dataflash(DataFlash_Class *dataflash)
bool try_send_mission_message(enum ap_message id)
static AP_SerialManager serial_manager
AP_HAL::Util::perf_counter_t _perf_packet
virtual void send_scaled_pressure3()
virtual uint32_t telem_delay() const =0
void handle_send_autopilot_version(const mavlink_message_t *msg)
virtual uint32_t custom_mode() const =0
void handle_global_vision_position_estimate(mavlink_message_t *msg)
Object managing Rally Points.
void send_to_components(const mavlink_message_t *msg)
void send_heartbeat(void) const
void set_ekf_origin(const Location &loc)
virtual void setup_uarts(AP_SerialManager &serial_manager)
void send_mission_item_reached_message(uint16_t mission_index)
void handle_gimbal_report(AP_Mount &mount, mavlink_message_t *msg) const
static uint8_t chan_is_streaming
uint8_t num_deferred_messages
MAVLink transport control class.
bool stream_trigger(enum streams stream_num)
void send_autopilot_version() const
uint32_t last_alternate_ms
const uint16_t interval_ms
MAV_RESULT handle_command_mag_cal(const mavlink_command_long_t &packet)
static ObjectBuffer< pending_param_reply > param_replies
void handle_timesync(mavlink_message_t *msg)
void send_vibration() const
virtual void handleMessage(mavlink_message_t *msg)=0
uint32_t last_heartbeat_time
AP_Param * _queued_parameter
next parameter to
void init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan)
static uint32_t reserve_param_space_start_ms
void handle_rally_point(mavlink_message_t *msg)
void send_parameter_value(const char *param_name, ap_var_type param_type, float param_value)
void lock_channel(mavlink_channel_t chan, bool lock)
MAV_RESULT handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet)
static const struct stream_entries all_stream_entries[]
void handle_device_op_write(mavlink_message_t *msg)
bool handle_mission_item(mavlink_message_t *msg, AP_Mission &mission)
struct GCS_MAVLINK::@196 alternative
bool send_battery_status() const
static AP_Frsky_Telem * frsky_telemetry_p
uint32_t correct_offboard_timestamp_usec_to_ms(uint64_t offboard_usec, uint16_t payload_size)
void handle_mission_request_list(AP_Mission &mission, mavlink_message_t *msg)
bool signing_enabled(void) const
float adjust_rate_for_stream_trigger(enum streams stream_num)
static uint8_t packet_overhead_chan(mavlink_channel_t chan)
void service_statustext(void)
uint32_t min_sample_counter
MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet, bool disable_overrides)
static bool find_by_mavtype(uint8_t mav_type, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel)
void handle_common_param_message(mavlink_message_t *msg)
void handle_vision_position_delta(mavlink_message_t *msg)
virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd)=0
void handle_mission_write_partial_list(AP_Mission &mission, mavlink_message_t *msg)
uint64_t timesync_receive_timestamp_ns() const
void handle_request_data_stream(mavlink_message_t *msg)
MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet)
enum ap_var_type _queued_parameter_type
type of the next
static uint32_t last_signing_save_ms
virtual const AP_FWVersion & get_fwver() const =0
DataFlash_Class * dataflash_p
virtual class AP_Camera * get_camera() const =0
void register_frsky_telemetry_callback(AP_Frsky_Telem *frsky_telemetry)
static uint8_t active_channel_mask(void)
mavlink_channel_t get_chan() const
void handle_att_pos_mocap(mavlink_message_t *msg)
struct GCS_MAVLINK::@197 lag_correction
void handle_statustext(mavlink_message_t *msg)
void send_rangefinder_downward() const
virtual MAV_STATE system_status() const =0
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 send_servo_output_raw()
virtual AP_Rally * get_rally() const =0
uint16_t waypoint_request_last
AP_HAL::Util::perf_counter_t _perf_update
static const AP_SerialManager * serialmanager_p
virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet)
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd)=0
bool telemetry_delayed() const
AP_HAL::UARTDriver * get_uart()
virtual bool set_mode(uint8_t mode)=0
virtual MAV_TYPE frame_type() const =0
void handle_common_message(mavlink_message_t *msg)
mavlink_signing_t signing
void queued_waypoint_send()
Send the next pending waypoint, called from deferred message handling code.
static ObjectBuffer< pending_param_request > param_requests
void send_queued_parameters(void)
bool try_send_gps_message(enum ap_message id)
void handle_param_request_list(mavlink_message_t *msg)
void handle_radio_status(mavlink_message_t *msg, DataFlash_Class &dataflash, bool log_radio)
void send_parameter_reply(void)
const ap_message * ap_message_ids
virtual AP_VisualOdom * get_visual_odom() const
virtual void handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg)
bool send_proximity() const
void handle_mission_count(AP_Mission &mission, mavlink_message_t *msg)
MAV_RESULT handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
static MAVLink_routing routing
const uint8_t num_ap_message_ids
virtual float vfr_hud_airspeed() const
virtual void send_attitude() const
bool try_send_compass_message(enum ap_message id)
const uint16_t waypoint_receive_timeout
uint16_t waypoint_dest_sysid
void handle_vicon_position_estimate(mavlink_message_t *msg)
virtual void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text)
MAV_RESULT handle_command_do_send_banner(const mavlink_command_long_t &packet)
virtual uint8_t sysid_my_gcs() const =0
static OpticalFlow optflow
void send_local_position() const
virtual int32_t global_position_int_relative_alt() const
static StorageAccess _signing_storage
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
void set_out_of_time(bool val)
virtual void send_position_target_global_int()
uint16_t mission_item_reached_index
MAV_RESULT handle_command_do_set_mode(const mavlink_command_long_t &packet)
MAV_RESULT handle_servorelay_message(mavlink_command_long_t &packet)
void setup_uart(const AP_SerialManager &serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance)
void handle_common_mission_message(mavlink_message_t *msg)
uint16_t _queued_parameter_count
saved count of
static uint32_t last_radio_status_remrssi_ms
struct Location global_position_current_loc
void send_ekf_origin() const
virtual MAV_RESULT _handle_command_preflight_calibration_baro()
MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet)
void send_power_status(void)
void handle_data_packet(mavlink_message_t *msg)
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)
uint16_t packet_drops
so that we can report to a GCS the number of parameters it should
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void handle_mission_clear_all(AP_Mission &mission, mavlink_message_t *msg)
void handle_serial_control(const mavlink_message_t *msg)
virtual int16_t vfr_hud_throttle() const
void push_deferred_messages()
void queued_param_send()
Send the next pending parameter, called from deferred message handling code.
void handle_common_camera_message(const mavlink_message_t *msg)
static void disable_channel_routing(mavlink_channel_t chan)
virtual void send_simstate() const
virtual bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg)
void send_named_float(const char *name, float value) const
AP_BattMonitor & battery()
uint32_t waypoint_timelast_receive
MAV_RESULT handle_command_long_message(mavlink_command_long_t &packet)
Common definitions and utility routines for the ArduPilot libraries.
void handle_setup_signing(const mavlink_message_t *msg)
virtual MAV_MODE base_mode() const =0
static const struct AP_Param::GroupInfo var_info[]
virtual int32_t global_position_int_alt() const
virtual bool persist_streamrates() const
static const uint8_t num_gcs
AP_HAL::UARTDriver * _port
The stream we are communicating over.
uint32_t get_last_heartbeat_time() const
char _perf_update_name[16]
uint8_t stream_ticks[NUM_STREAMS]
virtual bool vfr_hud_make_alt_relative() const
MAV_RESULT _set_mode_common(const MAV_MODE base_mode, const uint32_t custom_mode)
enum ap_message deferred_messages[MSG_LAST]
#define AP_MISSION_CMD_INDEX_NONE
static uint8_t streaming_channel_mask(void)
void handle_mission_request(AP_Mission &mission, mavlink_message_t *msg)
AP_Frsky_Telem * frsky_telemetry_p
void load_signing_key(void)
static class GCS * instance()
uint8_t next_deferred_message
virtual AP_Mission * get_mission()=0
static void save_signing_timestamp(bool force_save_now)
void handle_param_request_read(mavlink_message_t *msg)
static mavlink_signing_streams_t signing_streams
MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet)
void handle_set_mode(mavlink_message_t *msg)
void send_sensor_offsets()
GCS_MAVLINK::protocol_handler_fn_t handler
virtual bool params_ready() const
uint32_t _queued_parameter_send_time_ms
static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour)
uint8_t packet_overhead(void) const
virtual AP_AdvancedFailsafe * get_advanced_failsafe() const
static bool signing_key_save(const struct SigningKey &key)
void handle_set_gps_global_origin(const mavlink_message_t *msg)
virtual void packetReceived(const mavlink_status_t &status, mavlink_message_t &msg)
uint32_t waypoint_timelast_request
void send_scaled_pressure()
void param_io_timer(void)
char _perf_packet_name[16]
void send_global_position_int()
handle routing of MAVLink packets by sysid/componentid
void send_message(enum ap_message id)
void panic(const char *errormsg,...) FMT_PRINTF(1
virtual void handle_command_ack(const mavlink_message_t *msg)
bool install_alternative_protocol(mavlink_channel_t chan, GCS_MAVLINK::protocol_handler_fn_t handler)
virtual MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet)
static bool param_timer_registered
virtual bool in_hil_mode() const
static bool signing_key_load(struct SigningKey &key)
void send_accelcal_vehicle_position(uint32_t position)
virtual bool try_send_message(enum ap_message id)
void update(uint32_t max_time_us=1000)
void handle_common_rally_message(mavlink_message_t *msg)
static uint8_t mavlink_active
static void update_signing_timestamp(uint64_t timestamp_usec)
Photo or video camera manager, with EEPROM-backed storage of constants.
uint16_t waypoint_request_i
bool try_send_camera_message(enum ap_message id)
virtual Compass * get_compass() const =0
bool find_by_mavtype(uint8_t mavtype, uint8_t &sysid, uint8_t &compid, mavlink_channel_t &channel)
void handle_vision_position_estimate(mavlink_message_t *msg)
FUNCTOR_TYPEDEF(protocol_handler_fn_t, bool, uint8_t, AP_HAL::UARTDriver *)
AP_Int16 streamRates[NUM_STREAMS]
uint64_t timesync_timestamp_ns() const
bool send_distance_sensor() const
void handle_rally_fetch_point(mavlink_message_t *msg)
virtual float vfr_hud_climbrate() const
virtual MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet)
struct GCS_MAVLINK::@195 _timesync_request
void handle_common_gps_message(mavlink_message_t *msg)