2016-08-25 04:48:27 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
|
|
|
#include "GCS_Mavlink.h"
|
|
|
|
|
|
|
|
class GCS_Plane : public GCS
|
|
|
|
{
|
2017-02-13 06:58:12 -04:00
|
|
|
friend class Plane; // for access to _chan in parameter declarations
|
2016-08-25 04:48:27 -03:00
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
// return GCS link at offset ofs
|
2019-06-18 07:37:53 -03:00
|
|
|
GCS_MAVLINK_Plane *chan(const uint8_t ofs) override {
|
|
|
|
if (ofs > _num_gcs) {
|
2020-04-29 21:40:47 -03:00
|
|
|
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
2019-06-18 07:37:53 -03:00
|
|
|
return nullptr;
|
2019-06-24 23:58:00 -03:00
|
|
|
}
|
2019-06-18 07:37:53 -03:00
|
|
|
return (GCS_MAVLINK_Plane *)_chan[ofs];
|
2019-06-24 23:58:00 -03:00
|
|
|
}
|
2019-06-18 07:37:53 -03:00
|
|
|
const GCS_MAVLINK_Plane *chan(const uint8_t ofs) const override {
|
|
|
|
if (ofs > _num_gcs) {
|
2020-04-29 21:40:47 -03:00
|
|
|
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
2019-06-18 07:37:53 -03:00
|
|
|
return nullptr;
|
2019-06-24 23:58:00 -03:00
|
|
|
}
|
2019-06-18 07:37:53 -03:00
|
|
|
return (GCS_MAVLINK_Plane *)_chan[ofs];
|
2019-06-24 23:58:00 -03:00
|
|
|
}
|
2016-08-25 04:48:27 -03:00
|
|
|
|
2019-02-13 22:25:10 -04:00
|
|
|
protected:
|
|
|
|
|
2020-02-11 21:01:17 -04:00
|
|
|
uint8_t sysid_this_mav() const override;
|
2019-02-19 21:17:46 -04:00
|
|
|
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;
|
2019-02-13 20:43:03 -04:00
|
|
|
|
2019-06-18 07:37:53 -03:00
|
|
|
GCS_MAVLINK_Plane *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
|
|
|
AP_HAL::UARTDriver &uart) override {
|
|
|
|
return new GCS_MAVLINK_Plane(params, uart);
|
|
|
|
}
|
2019-11-08 02:59:42 -04:00
|
|
|
|
|
|
|
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
|
|
|
};
|