Display.h 1.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142
  1. #pragma once
  2. #include "NotifyDevice.h"
  3. #define ROW(Y) ((Y * 10) + 6)
  4. #define COLUMN(X) ((X * 7) + 0)
  5. #define DISPLAY_MESSAGE_SIZE 19
  6. class Display_Backend;
  7. class Display: public NotifyDevice {
  8. public:
  9. friend class Display_Backend;
  10. bool init(void) override;
  11. void update() override;
  12. private:
  13. void draw_char(uint16_t x, uint16_t y, const char c);
  14. void draw_text(uint16_t x, uint16_t y, const char *c);
  15. void update_all();
  16. void update_arm(uint8_t r);
  17. void update_prearm(uint8_t r);
  18. void update_gps(uint8_t r);
  19. void update_gps_sats(uint8_t r);
  20. void update_ekf(uint8_t r);
  21. void update_battery(uint8_t r);
  22. void update_mode(uint8_t r);
  23. void update_text(uint8_t r);
  24. void update_text_empty(uint8_t r);
  25. Display_Backend *_driver;
  26. uint8_t _mstartpos; // ticker shift position
  27. uint8_t _movedelay; // ticker delay before shifting after new message displayed
  28. uint8_t _screenpage;
  29. // stop showing text in display after this many millis:
  30. const uint16_t _send_text_valid_millis = 20000;
  31. };