ardupilot/ArduPlane/GCS_Plane.h

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

36 lines
1.1 KiB
C
Raw Normal View History

2016-08-25 04:48:27 -03:00
#pragma once
#include <GCS_MAVLink/GCS.h>
#include "GCS_Mavlink.h"
class GCS_Plane : public GCS
{
friend class Plane; // for access to _chan in parameter declarations
2016-08-25 04:48:27 -03:00
public:
// the following define expands to a pair of methods to retrieve a
// pointer to an object of the correct subclass for the link at
// offset ofs. These are of the form:
// GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override;
// const GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override const;
GCS_MAVLINK_CHAN_METHOD_DEFINITIONS(GCS_MAVLINK_Plane);
2016-08-25 04:48:27 -03:00
protected:
uint8_t sysid_this_mav() const override;
void update_vehicle_sensor_status_flags(void) override;
2019-03-01 02:27:53 -04:00
uint32_t custom_mode() const override;
MAV_TYPE frame_type() const override;
GCS_MAVLINK_Plane *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params,
AP_HAL::UARTDriver &uart) override {
return NEW_NOTHROW GCS_MAVLINK_Plane(params, uart);
}
AP_GPS::GPS_Status min_status_for_gps_healthy() const override {
// NO_FIX simply excludes NO_GPS
return AP_GPS::GPS_OK_FIX_3D;
}
2016-08-25 04:48:27 -03:00
};