APM:Libraries
Display.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "NotifyDevice.h"
4 
5 #define ROW(Y) ((Y * 10) + 6)
6 #define COLUMN(X) ((X * 7) + 0)
7 
8 #define DISPLAY_MESSAGE_SIZE 19
9 
10 class Display_Backend;
11 
12 class Display: public NotifyDevice {
13 public:
14  friend class Display_Backend;
15 
16  bool init(void);
17  void update();
18 
19 private:
20  void draw_char(uint16_t x, uint16_t y, const char c);
21  void draw_text(uint16_t x, uint16_t y, const char *c);
22  void update_all();
23  void update_arm(uint8_t r);
24  void update_prearm(uint8_t r);
25  void update_gps(uint8_t r);
26  void update_gps_sats(uint8_t r);
27  void update_ekf(uint8_t r);
28  void update_battery(uint8_t r);
29  void update_mode(uint8_t r);
30  void update_text(uint8_t r);
31  void update_text_empty(uint8_t r);
32 
34 
35  bool _healthy;
36 
37  uint8_t _mstartpos; // ticker shift position
38  uint8_t _movedelay; // ticker delay before shifting after new message displayed
39  uint8_t _screenpage;
40 
41  // stop showing text in display after this many millis:
42  const uint16_t _send_text_valid_millis = 20000;
43 };
44 
void update_prearm(uint8_t r)
Definition: Display.cpp:458
void update_text_empty(uint8_t r)
Definition: Display.cpp:534
void update_battery(uint8_t r)
Definition: Display.cpp:518
bool _healthy
Definition: Display.h:35
uint8_t _mstartpos
Definition: Display.h:37
uint8_t _movedelay
Definition: Display.h:38
void update_gps_sats(uint8_t r)
Definition: Display.cpp:502
void update_text(uint8_t r)
Definition: Display.cpp:543
void update_mode(uint8_t r)
Definition: Display.cpp:525
void draw_char(uint16_t x, uint16_t y, const char c)
Definition: Display.cpp:426
#define x(i)
void update_ekf(uint8_t r)
Definition: Display.cpp:509
uint8_t _screenpage
Definition: Display.h:39
const uint16_t _send_text_valid_millis
Definition: Display.h:42
void update()
Definition: Display.cpp:360
bool init(void)
Definition: Display.cpp:320
Display_Backend * _driver
Definition: Display.h:33
void update_all()
Definition: Display.cpp:394
void update_gps(uint8_t r)
Definition: Display.cpp:467
void update_arm(uint8_t r)
Definition: Display.cpp:449
void draw_text(uint16_t x, uint16_t y, const char *c)
Definition: Display.cpp:405