2017-07-02 19:58:45 -03:00
|
|
|
#include "GCS.h"
|
|
|
|
|
2017-08-18 20:07:42 -03:00
|
|
|
const AP_FWVersion fwver
|
|
|
|
{
|
|
|
|
major: 3,
|
|
|
|
minor: 1,
|
|
|
|
patch: 4,
|
|
|
|
fw_type: FIRMWARE_VERSION_TYPE_DEV,
|
|
|
|
fw_string: "Dummy GCS"
|
|
|
|
};
|
|
|
|
|
2017-07-02 19:58:45 -03:00
|
|
|
/*
|
|
|
|
* GCS backend used for many examples and tools
|
|
|
|
*/
|
|
|
|
class GCS_MAVLINK_Dummy : public GCS_MAVLINK
|
|
|
|
{
|
|
|
|
void data_stream_send(void) override {}
|
|
|
|
uint32_t telem_delay() const override { return 0; }
|
|
|
|
void handleMessage(mavlink_message_t * msg) override {}
|
|
|
|
bool try_send_message(enum ap_message id) { return true; }
|
|
|
|
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return true; }
|
|
|
|
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override {}
|
2017-07-08 06:09:06 -03:00
|
|
|
|
|
|
|
protected:
|
|
|
|
|
2017-07-16 21:46:54 -03:00
|
|
|
Compass *get_compass() const override { return nullptr; };
|
2017-07-08 06:09:06 -03:00
|
|
|
AP_Mission *get_mission() override { return nullptr; }
|
2017-07-12 21:20:45 -03:00
|
|
|
AP_Rally *get_rally() const override { return nullptr; };
|
2017-07-25 04:01:47 -03:00
|
|
|
AP_GPS *get_gps() const override { return nullptr; };
|
2017-07-26 02:48:01 -03:00
|
|
|
AP_Camera *get_camera() const override { return nullptr; };
|
2017-07-13 23:44:21 -03:00
|
|
|
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
2017-08-18 20:07:42 -03:00
|
|
|
const AP_FWVersion &get_fwver() const override { return fwver; }
|
2017-09-18 23:30:32 -03:00
|
|
|
void set_ekf_origin(const Location& loc) override { };
|
2017-07-12 21:20:45 -03:00
|
|
|
|
2017-07-12 04:21:15 -03:00
|
|
|
uint8_t sysid_my_gcs() const override { return 1; }
|
2017-08-11 02:52:09 -03:00
|
|
|
bool set_mode(uint8_t mode) override { return false; };
|
2017-07-08 06:09:06 -03:00
|
|
|
|
2017-07-02 19:58:45 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
/*
|
|
|
|
* a GCS singleton used for many example sketches and tools
|
|
|
|
*/
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
class GCS_Dummy : public GCS
|
|
|
|
{
|
|
|
|
GCS_MAVLINK_Dummy dummy_backend;
|
|
|
|
uint8_t num_gcs() const override { return 1; }
|
2017-07-08 04:58:51 -03:00
|
|
|
GCS_MAVLINK_Dummy &chan(const uint8_t ofs) override { return dummy_backend; }
|
|
|
|
const GCS_MAVLINK_Dummy &chan(const uint8_t ofs) const override { return dummy_backend; };
|
2017-07-02 19:58:45 -03:00
|
|
|
|
|
|
|
void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text) { hal.console->printf("TOGCS: %s\n", text); }
|
|
|
|
};
|