2017-07-02 19:58:45 -03:00
|
|
|
#include "GCS.h"
|
2019-04-04 07:49:44 -03:00
|
|
|
#include <AP_Common/AP_FWVersion.h>
|
2017-07-02 19:58:45 -03:00
|
|
|
|
2020-09-24 12:17:58 -03:00
|
|
|
#define THISFIRMWARE "GCSDummy V3.1.4-dev"
|
|
|
|
|
|
|
|
#define FW_MAJOR 3
|
|
|
|
#define FW_MINOR 1
|
|
|
|
#define FW_PATCH 4
|
|
|
|
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV
|
|
|
|
|
2017-07-02 19:58:45 -03:00
|
|
|
/*
|
|
|
|
* GCS backend used for many examples and tools
|
|
|
|
*/
|
|
|
|
class GCS_MAVLINK_Dummy : public GCS_MAVLINK
|
|
|
|
{
|
2018-12-10 03:56:32 -04:00
|
|
|
public:
|
|
|
|
|
|
|
|
using GCS_MAVLINK::GCS_MAVLINK;
|
|
|
|
|
|
|
|
private:
|
|
|
|
|
2017-07-02 19:58:45 -03:00
|
|
|
uint32_t telem_delay() const override { return 0; }
|
2019-07-11 05:31:45 -03:00
|
|
|
void handleMessage(const mavlink_message_t &msg) override {}
|
2019-04-16 01:13:17 -03:00
|
|
|
bool try_send_message(enum ap_message id) override { return true; }
|
2017-07-02 19:58:45 -03:00
|
|
|
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return true; }
|
2017-07-08 06:09:06 -03:00
|
|
|
|
|
|
|
protected:
|
|
|
|
|
2017-07-12 04:21:15 -03:00
|
|
|
uint8_t sysid_my_gcs() const override { return 1; }
|
2017-07-08 06:09:06 -03:00
|
|
|
|
2018-03-22 05:49:33 -03:00
|
|
|
// dummy information:
|
|
|
|
MAV_MODE base_mode() const override { return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }
|
2019-11-24 17:24:44 -04:00
|
|
|
MAV_STATE vehicle_system_status() const override { return MAV_STATE_CALIBRATING; }
|
2018-03-22 05:49:33 -03:00
|
|
|
|
2019-09-12 03:14:55 -03:00
|
|
|
bool set_home_to_current_location(bool _lock) override { return false; }
|
|
|
|
bool set_home(const Location& loc, bool _lock) override { return false; }
|
2018-05-04 21:07:59 -03:00
|
|
|
|
|
|
|
void send_nav_controller_output() const override {};
|
2019-02-28 19:24:13 -04:00
|
|
|
void send_pid_tuning() override {};
|
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
|
|
|
|
{
|
2018-12-10 03:56:32 -04:00
|
|
|
public:
|
|
|
|
|
|
|
|
using GCS::GCS;
|
|
|
|
|
|
|
|
protected:
|
|
|
|
|
2020-02-11 21:01:17 -04:00
|
|
|
uint8_t sysid_this_mav() const override { return 1; }
|
|
|
|
|
2018-12-10 03:56:32 -04:00
|
|
|
GCS_MAVLINK_Dummy *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
|
|
|
AP_HAL::UARTDriver &uart) override {
|
|
|
|
return new GCS_MAVLINK_Dummy(params, uart);
|
|
|
|
}
|
|
|
|
|
|
|
|
private:
|
|
|
|
GCS_MAVLINK_Dummy *chan(const uint8_t ofs) override {
|
|
|
|
if (ofs > _num_gcs) {
|
2020-04-29 21:40:46 -03:00
|
|
|
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
2018-12-10 03:56:32 -04:00
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
return (GCS_MAVLINK_Dummy *)_chan[ofs];
|
|
|
|
};
|
|
|
|
const GCS_MAVLINK_Dummy *chan(const uint8_t ofs) const override {
|
|
|
|
if (ofs > _num_gcs) {
|
2020-04-29 21:40:46 -03:00
|
|
|
INTERNAL_ERROR(AP_InternalError::error_t::gcs_offset);
|
2018-12-10 03:56:32 -04:00
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
return (GCS_MAVLINK_Dummy *)_chan[ofs];
|
|
|
|
};
|
2017-07-02 19:58:45 -03:00
|
|
|
|
2020-11-08 23:51:13 -04:00
|
|
|
void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, uint8_t dest_bitmask) override;
|
2019-02-13 20:39:32 -04:00
|
|
|
|
2019-02-12 07:54:24 -04:00
|
|
|
MAV_TYPE frame_type() const override { return MAV_TYPE_FIXED_WING; }
|
|
|
|
uint32_t custom_mode() const override { return 3; } // magic number
|
2017-07-02 19:58:45 -03:00
|
|
|
};
|