#pragma once12#include <GCS_MAVLink/GCS.h>3#include "GCS_MAVLink_Blimp.h"45class GCS_Blimp : public GCS6{7friend class Blimp; // 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_Blimp);1718void update_vehicle_sensor_status_flags(void) override;1920uint32_t custom_mode() const override;21MAV_TYPE frame_type() const override;2223const char* frame_string() const override;2425bool vehicle_initialised() const override;2627protected:2829// minimum amount of time (in microseconds) that must remain in30// the main scheduler loop before we are allowed to send any31// mavlink messages. We want to prioritise the main flight32// control loop over communications33uint16_t min_loop_time_remaining_for_message_send_us() const override34{35return 250;36}3738GCS_MAVLINK_Blimp *new_gcs_mavlink_backend(AP_HAL::UARTDriver &uart) override39{40return NEW_NOTHROW GCS_MAVLINK_Blimp(uart);41}4243};444546