2016-05-27 10:14:08 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
|
|
|
|
|
|
|
class GCS_MAVLINK_Tracker : public GCS_MAVLINK
|
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
void data_stream_send(void) override;
|
|
|
|
|
|
|
|
protected:
|
|
|
|
|
2016-05-29 21:17:24 -03:00
|
|
|
// telem_delay is not used by Tracker but is pure virtual, thus
|
|
|
|
// this implementaiton. it probably *should* be used by Tracker,
|
|
|
|
// as currently Tracker may brick XBees
|
2016-07-01 02:34:44 -03:00
|
|
|
uint32_t telem_delay() const override { return 0; }
|
2016-05-29 21:17:24 -03:00
|
|
|
|
2017-07-16 21:47:16 -03:00
|
|
|
Compass *get_compass() const override;
|
2017-07-08 00:49:17 -03:00
|
|
|
AP_Mission *get_mission() override { return nullptr; };
|
2017-07-12 21:48:09 -03:00
|
|
|
AP_Rally *get_rally() const override { return nullptr; };
|
2017-07-26 03:35:27 -03:00
|
|
|
AP_Camera *get_camera() const override { return nullptr; };
|
2017-07-14 19:36:47 -03:00
|
|
|
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
2017-07-25 04:07:26 -03:00
|
|
|
AP_GPS *get_gps() const override;
|
2017-08-19 06:53:15 -03:00
|
|
|
const AP_FWVersion &get_fwver() const override;
|
2017-09-18 23:42:32 -03:00
|
|
|
void set_ekf_origin(const Location& loc) override;
|
2017-07-12 21:48:09 -03:00
|
|
|
|
2017-07-12 04:51:08 -03:00
|
|
|
uint8_t sysid_my_gcs() const override;
|
2017-07-08 00:49:17 -03:00
|
|
|
|
2017-08-11 03:15:34 -03:00
|
|
|
bool set_mode(uint8_t mode) override;
|
|
|
|
|
2016-05-27 10:14:08 -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;
|
|
|
|
|
|
|
|
};
|