ardupilot/libraries/AP_Notify/Display.h

45 lines
1.0 KiB
C
Raw Normal View History

2015-12-22 17:16:19 -04:00
#pragma once
#include "NotifyDevice.h"
#define ROW(Y) ((Y * 10) + 6)
#define COLUMN(X) ((X * 7) + 0)
#define DISPLAY_MESSAGE_SIZE 19
2015-12-22 17:16:19 -04:00
class Display_Backend;
2015-12-22 17:16:19 -04:00
class Display: public NotifyDevice {
public:
friend class Display_Backend;
2015-12-22 17:16:19 -04:00
bool init(void);
void update();
private:
void draw_char(uint16_t x, uint16_t y, const char c);
void draw_text(uint16_t x, uint16_t y, const char *c);
void update_all();
void update_arm(uint8_t r);
void update_prearm(uint8_t r);
void update_gps(uint8_t r);
void update_gps_sats(uint8_t r);
void update_ekf(uint8_t r);
void update_battery(uint8_t r);
void update_mode(uint8_t r);
void update_text(uint8_t r);
void update_text_empty(uint8_t r);
2015-12-22 17:16:19 -04:00
Display_Backend *_driver;
2015-12-22 17:16:19 -04:00
bool _healthy;
uint8_t _mstartpos; // ticker shift position
uint8_t _movedelay; // ticker delay before shifting after new message displayed
uint8_t _screenpage;
// stop showing text in display after this many millis:
const uint16_t _send_text_valid_millis = 20000;
2015-12-22 17:16:19 -04:00
};