AP_Notify: Display bus passed into contructor

This commit is contained in:
Randy Mackay 2017-01-20 15:42:53 +09:00 committed by Lucas De Marchi
parent 682fc759f1
commit 843210cac2
6 changed files with 21 additions and 13 deletions

View File

@ -23,6 +23,8 @@
#include <stdio.h> #include <stdio.h>
#include <AP_GPS/AP_GPS.h> #include <AP_GPS/AP_GPS.h>
extern const AP_HAL::HAL& hal;
static const uint8_t _font[] = { static const uint8_t _font[] = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x3E, 0x5B, 0x4F, 0x5B, 0x3E, 0x3E, 0x5B, 0x4F, 0x5B, 0x3E,
@ -367,11 +369,11 @@ bool Display::init(void)
// initialise driver // initialise driver
switch (pNotify->_display_type) { switch (pNotify->_display_type) {
case DISPLAY_SSD1306: case DISPLAY_SSD1306:
_driver = new Display_SSD1306_I2C(); _driver = new Display_SSD1306_I2C(hal.i2c_mgr->get_device(NOTIFY_DISPLAY_I2C_BUS, NOTIFY_DISPLAY_I2C_ADDR));
break; break;
case DISPLAY_SH1106: case DISPLAY_SH1106:
_driver = new Display_SH1106_I2C(); _driver = new Display_SH1106_I2C(hal.i2c_mgr->get_device(NOTIFY_DISPLAY_I2C_BUS, NOTIFY_DISPLAY_I2C_ADDR));
break; break;
case DISPLAY_OFF: case DISPLAY_OFF:

View File

@ -3,10 +3,11 @@
#include "Display.h" #include "Display.h"
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
#define OLED_I2C_BUS 2 #define NOTIFY_DISPLAY_I2C_BUS 2
#else #else
#define OLED_I2C_BUS 1 #define NOTIFY_DISPLAY_I2C_BUS 1
#endif #endif
#define NOTIFY_DISPLAY_I2C_ADDR 0x3C
class Display_Backend { class Display_Backend {

View File

@ -19,10 +19,12 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h> #include <AP_HAL/I2CDevice.h>
#define SH1106_I2C_ADDR 0x3C // default I2C bus address
static const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// constructor
Display_SH1106_I2C::Display_SH1106_I2C(AP_HAL::OwnPtr<AP_HAL::Device> dev) :
_dev(std::move(dev)) {}
bool Display_SH1106_I2C::hw_init() bool Display_SH1106_I2C::hw_init()
{ {
struct { struct {
@ -48,7 +50,6 @@ bool Display_SH1106_I2C::hw_init()
0x02, 0x10 // Column Address 0x02, 0x10 // Column Address
} }; } };
_dev = std::move(hal.i2c_mgr->get_device(OLED_I2C_BUS, SH1106_I2C_ADDR));
memset(_displaybuffer, 0, SH1106_COLUMNS * SH1106_ROWS_PER_PAGE); memset(_displaybuffer, 0, SH1106_COLUMNS * SH1106_ROWS_PER_PAGE);
// take i2c bus semaphore // take i2c bus semaphore

View File

@ -11,6 +11,8 @@
class Display_SH1106_I2C: public Display_Backend { class Display_SH1106_I2C: public Display_Backend {
public: public:
Display_SH1106_I2C(AP_HAL::OwnPtr<AP_HAL::Device> dev);
bool hw_init() override; bool hw_init() override;
bool hw_update() override; bool hw_update() override;
bool set_pixel(uint16_t x, uint16_t y) override; bool set_pixel(uint16_t x, uint16_t y) override;
@ -20,7 +22,7 @@ public:
private: private:
void _timer(); void _timer();
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev; AP_HAL::OwnPtr<AP_HAL::Device> _dev;
uint8_t _displaybuffer[SH1106_COLUMNS * SH1106_ROWS_PER_PAGE]; uint8_t _displaybuffer[SH1106_COLUMNS * SH1106_ROWS_PER_PAGE];
bool _need_hw_update; bool _need_hw_update;
}; };

View File

@ -19,10 +19,11 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h> #include <AP_HAL/I2CDevice.h>
#define SSD1306_I2C_ADDR 0x3C // default I2C bus address
static const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// constructor
Display_SSD1306_I2C::Display_SSD1306_I2C(AP_HAL::OwnPtr<AP_HAL::Device> dev) :
_dev(std::move(dev)) {}
bool Display_SSD1306_I2C::hw_init() bool Display_SSD1306_I2C::hw_init()
{ {
@ -57,7 +58,6 @@ bool Display_SSD1306_I2C::hw_init()
0x22, 0, 7 // +++ Page Address: (== start:0, end:7) 0x22, 0, 7 // +++ Page Address: (== start:0, end:7)
} }; } };
_dev = std::move(hal.i2c_mgr->get_device(OLED_I2C_BUS, SSD1306_I2C_ADDR));
memset(_displaybuffer, 0, SSD1306_COLUMNS * SSD1306_ROWS_PER_PAGE); memset(_displaybuffer, 0, SSD1306_COLUMNS * SSD1306_ROWS_PER_PAGE);
// take i2c bus semaphore // take i2c bus semaphore

View File

@ -11,6 +11,8 @@
class Display_SSD1306_I2C: public Display_Backend { class Display_SSD1306_I2C: public Display_Backend {
public: public:
Display_SSD1306_I2C(AP_HAL::OwnPtr<AP_HAL::Device> dev);
bool hw_init() override; bool hw_init() override;
bool hw_update() override; bool hw_update() override;
bool set_pixel(uint16_t x, uint16_t y) override; bool set_pixel(uint16_t x, uint16_t y) override;
@ -20,7 +22,7 @@ public:
private: private:
void _timer(); void _timer();
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev; AP_HAL::OwnPtr<AP_HAL::Device> _dev;
uint8_t _displaybuffer[SSD1306_COLUMNS * SSD1306_ROWS_PER_PAGE]; uint8_t _displaybuffer[SSD1306_COLUMNS * SSD1306_ROWS_PER_PAGE];
bool _need_hw_update; bool _need_hw_update;
}; };