#pragma once12#include <GCS_MAVLink/GCS.h>3#include "GCS_MAVLink_Sub.h"45class GCS_Sub : public GCS6{7friend class Sub; // for access to _chan in parameter declarations89public:1011// the following define expands to a pair of methods to retrieve a12// pointer to an object of the correct subclass for the link at13// offset ofs. These are of the form:14// GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override;15// const GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override const;16GCS_MAVLINK_CHAN_METHOD_DEFINITIONS(GCS_MAVLINK_Sub);1718void update_vehicle_sensor_status_flags() override;1920uint32_t custom_mode() const override;21MAV_TYPE frame_type() const override;2223bool vehicle_initialised() const override;2425protected:2627// minimum amount of time (in microseconds) that must remain in28// the main scheduler loop before we are allowed to send any29// mavlink messages. We want to prioritise the main flight30// control loop over communications31uint16_t min_loop_time_remaining_for_message_send_us() const override {32return 250;33}3435GCS_MAVLINK_Sub *new_gcs_mavlink_backend(AP_HAL::UARTDriver &uart) override {36return NEW_NOTHROW GCS_MAVLINK_Sub(uart);37}3839};404142