GCS_Sub.h 1.5 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950
  1. #pragma once
  2. #include <GCS_MAVLink/GCS.h>
  3. #include "GCS_Mavlink.h"
  4. class GCS_Sub : public GCS
  5. {
  6. friend class Sub; // for access to _chan in parameter declarations
  7. public:
  8. // return GCS link at offset ofs
  9. GCS_MAVLINK_Sub *chan(const uint8_t ofs) override {
  10. if (ofs > _num_gcs) {
  11. AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
  12. return nullptr;
  13. }
  14. return (GCS_MAVLINK_Sub*)_chan[ofs];
  15. }
  16. const GCS_MAVLINK_Sub *chan(const uint8_t ofs) const override {
  17. if (ofs > _num_gcs) {
  18. AP::internalerror().error(AP_InternalError::error_t::gcs_offset);
  19. return nullptr;
  20. }
  21. return (GCS_MAVLINK_Sub*)_chan[ofs];
  22. }
  23. void update_vehicle_sensor_status_flags() override;
  24. uint32_t custom_mode() const override;
  25. MAV_TYPE frame_type() const override;
  26. bool vehicle_initialised() const override;
  27. protected:
  28. // minimum amount of time (in microseconds) that must remain in
  29. // the main scheduler loop before we are allowed to send any
  30. // mavlink messages. We want to prioritise the main flight
  31. // control loop over communications
  32. uint16_t min_loop_time_remaining_for_message_send_us() const override {
  33. return 250;
  34. }
  35. GCS_MAVLINK_Sub *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params,
  36. AP_HAL::UARTDriver &uart) override {
  37. return new GCS_MAVLINK_Sub(params, uart);
  38. }
  39. };