forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 25
/
Copy pathGCS_Plane.h
35 lines (27 loc) · 1.11 KB
/
GCS_Plane.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
#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
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);
protected:
uint8_t sysid_this_mav() const override;
void update_vehicle_sensor_status_flags(void) override;
uint32_t custom_mode() const override;
MAV_TYPE frame_type() const override;
GCS_MAVLINK_Plane *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
AP_HAL::UARTDriver &uart) override {
return new 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;
}
};