Path: blob/master/AntennaTracker/GCS_MAVLink_Tracker.h
9726 views
#pragma once12#include <GCS_MAVLink/GCS.h>34class GCS_MAVLINK_Tracker : public GCS_MAVLINK5{67public:89using GCS_MAVLINK::GCS_MAVLINK;1011protected:1213MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet) override;14MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override;15MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;1617int32_t global_position_int_relative_alt() const override {18return 0; // what if we have been picked up and carried somewhere?19}2021void send_attitude_target() override;22void send_nav_controller_output() const override;23void send_pid_tuning() override;2425// Send the mode with the given index (not mode number!) return the total number of modes26// Index starts at 127uint8_t send_available_mode(uint8_t index) const override;2829bool try_send_message(enum ap_message id) override;3031private:3233void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;34void mavlink_check_target(const mavlink_message_t &msg);35void handle_message(const mavlink_message_t &msg) override;36void handle_message_mission_write_partial_list(const mavlink_message_t &msg);37void handle_message_mission_item(const mavlink_message_t &msg);38void handle_message_manual_control(const mavlink_message_t &msg);39void handle_message_global_position_int(const mavlink_message_t &msg);40void handle_message_scaled_pressure(const mavlink_message_t &msg);41void handle_set_attitude_target(const mavlink_message_t &msg);4243void send_global_position_int() override;4445uint8_t base_mode() const override;46MAV_STATE vehicle_system_status() const override;4748bool waypoint_receiving;49};505152