GCS_Mavlink.h 1.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960
  1. #pragma once
  2. #include <GCS_MAVLink/GCS.h>
  3. class GCS_MAVLINK_Sub : public GCS_MAVLINK {
  4. public:
  5. using GCS_MAVLINK::GCS_MAVLINK;
  6. protected:
  7. uint32_t telem_delay() const override {
  8. return 0;
  9. };
  10. MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
  11. uint8_t sysid_my_gcs() const override;
  12. bool set_mode(uint8_t mode) override;
  13. bool should_zero_rc_outputs_on_reboot() const override { return true; }
  14. MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
  15. MAV_RESULT _handle_command_preflight_calibration_baro() override;
  16. MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override;
  17. MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
  18. // override sending of scaled_pressure3 to send on-board temperature:
  19. void send_scaled_pressure3() override;
  20. int32_t global_position_int_alt() const override;
  21. int32_t global_position_int_relative_alt() const override;
  22. bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
  23. bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
  24. void send_nav_controller_output() const override;
  25. void send_pid_tuning() override;
  26. uint64_t capabilities() const override;
  27. uint8_t get_battery_remaining_percentage(uint8_t instance) const override { return -1; };
  28. private:
  29. void handleMessage(const mavlink_message_t &msg) override;
  30. bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
  31. void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
  32. void handle_rc_channels_override(const mavlink_message_t &msg) override;
  33. bool try_send_message(enum ap_message id) override;
  34. bool send_info(void);
  35. MAV_MODE base_mode() const override;
  36. MAV_STATE system_status() const override;
  37. int16_t vfr_hud_throttle() const override;
  38. };