GCS_Dummy.h 2.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293
  1. #include "GCS.h"
  2. #include <AP_Common/AP_FWVersion.h>
  3. const AP_FWVersion AP_FWVersion::fwver
  4. {
  5. major: 3,
  6. minor: 1,
  7. patch: 4,
  8. fw_type: FIRMWARE_VERSION_TYPE_DEV,
  9. fw_string: "Dummy GCS",
  10. fw_hash_str: "",
  11. middleware_name: "",
  12. middleware_hash_str: "",
  13. os_name: "",
  14. os_hash_str: "",
  15. os_sw_version: 0
  16. };
  17. const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] {};
  18. /*
  19. * GCS backend used for many examples and tools
  20. */
  21. class GCS_MAVLINK_Dummy : public GCS_MAVLINK
  22. {
  23. public:
  24. using GCS_MAVLINK::GCS_MAVLINK;
  25. private:
  26. uint32_t telem_delay() const override { return 0; }
  27. void handleMessage(const mavlink_message_t &msg) override {}
  28. bool try_send_message(enum ap_message id) override { return true; }
  29. bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return true; }
  30. void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override {}
  31. protected:
  32. uint8_t sysid_my_gcs() const override { return 1; }
  33. bool set_mode(uint8_t mode) override { return false; };
  34. // dummy information:
  35. MAV_MODE base_mode() const override { return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }
  36. MAV_STATE system_status() const override { return MAV_STATE_CALIBRATING; }
  37. bool set_home_to_current_location(bool lock) override { return false; }
  38. bool set_home(const Location& loc, bool lock) override { return false; }
  39. void send_nav_controller_output() const override {};
  40. void send_pid_tuning() override {};
  41. };
  42. /*
  43. * a GCS singleton used for many example sketches and tools
  44. */
  45. extern const AP_HAL::HAL& hal;
  46. class GCS_Dummy : public GCS
  47. {
  48. public:
  49. using GCS::GCS;
  50. protected:
  51. GCS_MAVLINK_Dummy *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params,
  52. AP_HAL::UARTDriver &uart) override {
  53. return new GCS_MAVLINK_Dummy(params, uart);
  54. }
  55. private:
  56. GCS_MAVLINK_Dummy *chan(const uint8_t ofs) override {
  57. if (ofs > _num_gcs) {
  58. AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
  59. return nullptr;
  60. }
  61. return (GCS_MAVLINK_Dummy *)_chan[ofs];
  62. };
  63. const GCS_MAVLINK_Dummy *chan(const uint8_t ofs) const override {
  64. if (ofs > _num_gcs) {
  65. AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
  66. return nullptr;
  67. }
  68. return (GCS_MAVLINK_Dummy *)_chan[ofs];
  69. };
  70. void send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text) override { hal.console->printf("TOGCS: %s\n", text); }
  71. MAV_TYPE frame_type() const override { return MAV_TYPE_FIXED_WING; }
  72. uint32_t custom_mode() const override { return 3; } // magic number
  73. };