8 fw_type: FIRMWARE_VERSION_TYPE_DEV,
32 bool set_mode(uint8_t mode)
override {
return false; };
35 MAV_TYPE
frame_type()
const override {
return MAV_TYPE_FIXED_WING; }
36 MAV_MODE
base_mode()
const override {
return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }
38 MAV_STATE
system_status()
const override {
return MAV_STATE_CALIBRATING; }
51 uint8_t
num_gcs()
const override {
return 1; }
uint8_t sysid_my_gcs() const override
bool try_send_message(enum ap_message id)
Object managing Rally Points.
uint8_t num_gcs() const override
MAVLink transport control class.
AP_HAL::UARTDriver * console
const AP_FWVersion & get_fwver() const override
Interface definition for the various Ground Control System.
GCS_MAVLINK_Dummy dummy_backend
AP_Camera * get_camera() const override
const GCS_MAVLINK_Dummy & chan(const uint8_t ofs) const override
MAV_STATE system_status() const override
bool set_mode(uint8_t mode) override
MAV_TYPE frame_type() const override
MAV_MODE base_mode() const override
virtual void printf(const char *,...) FMT_PRINTF(2
AP_Mission * get_mission() override
GCS_MAVLINK_Dummy & chan(const uint8_t ofs) override
void handleMessage(mavlink_message_t *msg) override
Compass * get_compass() const override
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override
AP_Rally * get_rally() const override
uint32_t custom_mode() const override
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override
void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
uint32_t telem_delay() const override