2016-06-08 01:49:10 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
class GCS_MAVLINK_Sub : public GCS_MAVLINK {
|
2016-06-08 01:49:10 -03:00
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
void data_stream_send(void) override;
|
|
|
|
|
|
|
|
protected:
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
uint32_t telem_delay() const override {
|
|
|
|
return 0;
|
|
|
|
};
|
2016-06-08 01:49:10 -03:00
|
|
|
|
2017-07-16 21:47:40 -03:00
|
|
|
Compass *get_compass() const override;
|
2017-07-08 00:23:40 -03:00
|
|
|
AP_Mission *get_mission() override;
|
2017-07-12 21:48:56 -03:00
|
|
|
AP_Rally *get_rally() const override;
|
2017-07-13 23:54:06 -03:00
|
|
|
AP_ServoRelayEvents *get_servorelayevents() const override;
|
2017-07-25 04:09:08 -03:00
|
|
|
AP_GPS *get_gps() const override;
|
2017-07-12 21:48:56 -03:00
|
|
|
|
2017-07-12 04:51:23 -03:00
|
|
|
uint8_t sysid_my_gcs() const override;
|
2017-07-08 00:23:40 -03:00
|
|
|
|
2016-06-08 01:49:10 -03:00
|
|
|
private:
|
|
|
|
|
|
|
|
void handleMessage(mavlink_message_t * msg) override;
|
|
|
|
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
|
|
|
|
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
|
|
|
|
bool try_send_message(enum ap_message id) override;
|
|
|
|
|
|
|
|
};
|