Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
27 changes: 16 additions & 11 deletions libraries/AP_Notify/Display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,6 @@
#include <AP_GPS/AP_GPS.h>
#include <AP_BattMonitor/AP_BattMonitor.h>

#include <utility>

extern const AP_HAL::HAL& hal;

// Bit Map
Expand Down Expand Up @@ -327,6 +325,20 @@ static_assert(ARRAY_SIZE(_font) == 1280, "_font is correct size");
static_assert(ARRAY_SIZE(_font) == 475, "_font is correct size");
#endif

Display_Backend *Display::probe_i2c_display(uint8_t bus, probe_i2c_display_probefn_t probe)
{

const auto dev_ptr = hal.i2c_mgr->get_device_ptr(bus, NOTIFY_DISPLAY_I2C_ADDR);
if (dev_ptr == nullptr) {
return nullptr;
}
Display_Backend *ret = probe(*dev_ptr);
if (ret == nullptr) {
delete dev_ptr;
}
return ret;
}

bool Display::init(void)
{
// exit immediately if already initialised
Expand All @@ -338,18 +350,11 @@ bool Display::init(void)
FOREACH_I2C(i) {
switch (pNotify->_display_type) {
case DISPLAY_SSD1306: {
const auto dev_ptr = hal.i2c_mgr->get_device_ptr(i, NOTIFY_DISPLAY_I2C_ADDR);
if (dev_ptr == nullptr) {
break;
}
_driver = Display_SSD1306_I2C::probe(*dev_ptr);
if (_driver == nullptr) {
delete dev_ptr;
}
_driver = probe_i2c_display(i, Display_SSD1306_I2C::probe);
break;
}
case DISPLAY_SH1106: {
_driver = Display_SH1106_I2C::probe(std::move(hal.i2c_mgr->get_device(i, NOTIFY_DISPLAY_I2C_ADDR)));
_driver = probe_i2c_display(i, Display_SH1106_I2C::probe);
break;
}
case DISPLAY_SITL: {
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_Notify/Display.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,10 @@ class Display: public NotifyDevice {
void send_text_blocking(const char *text, uint8_t line) override;
void release_text(uint8_t line) override;
private:

using probe_i2c_display_probefn_t = Display_Backend* (*)(AP_HAL::Device&);
Display_Backend *probe_i2c_display(uint8_t bus, probe_i2c_display_probefn_t probe);

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();
Expand Down
37 changes: 9 additions & 28 deletions libraries/AP_Notify/Display_SH1106_I2C.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,24 +14,12 @@
*/
#include "Display_SH1106_I2C.h"

#include <utility>

#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/Device.h>

// constructor
Display_SH1106_I2C::Display_SH1106_I2C(AP_HAL::OwnPtr<AP_HAL::Device> dev) :
_dev(std::move(dev))
Display_Backend *Display_SH1106_I2C::probe(AP_HAL::Device &_dev)
{
}

Display_SH1106_I2C::~Display_SH1106_I2C()
{
}

Display_SH1106_I2C *Display_SH1106_I2C::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev)
{
Display_SH1106_I2C *driver = NEW_NOTHROW Display_SH1106_I2C(std::move(dev));
Display_SH1106_I2C *driver = NEW_NOTHROW Display_SH1106_I2C(_dev);
if (!driver || !driver->hw_init()) {
delete driver;
return nullptr;
Expand Down Expand Up @@ -67,21 +55,14 @@ bool Display_SH1106_I2C::hw_init()

memset(_displaybuffer, 0, SH1106_COLUMNS * SH1106_ROWS_PER_PAGE);

// take i2c bus semaphore
if (!_dev) {
return false;
}
_dev->get_semaphore()->take_blocking();
WITH_SEMAPHORE(dev.get_semaphore());

// init display
bool success = _dev->transfer((uint8_t *)&init_seq, sizeof(init_seq), nullptr, 0);

// give back i2c semaphore
_dev->get_semaphore()->give();
bool success = dev.transfer((uint8_t *)&init_seq, sizeof(init_seq), nullptr, 0);

if (success) {
_need_hw_update = true;
_dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&Display_SH1106_I2C::_timer, void));
dev.register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&Display_SH1106_I2C::_timer, void));
}

return success;
Expand Down Expand Up @@ -114,12 +95,12 @@ void Display_SH1106_I2C::_timer()
// write buffer to display
for (uint8_t i = 0; i < (SH1106_ROWS / SH1106_ROWS_PER_PAGE); i++) {
command.page = 0xB0 | (i & 0x0F);
_dev->transfer((uint8_t *)&command, sizeof(command), nullptr, 0);
dev.transfer((uint8_t *)&command, sizeof(command), nullptr, 0);

memcpy(&display_buffer.db[0], &_displaybuffer[i * SH1106_COLUMNS], SH1106_COLUMNS/2);
_dev->transfer((uint8_t *)&display_buffer, SH1106_COLUMNS/2 + 1, nullptr, 0);
dev.transfer((uint8_t *)&display_buffer, SH1106_COLUMNS/2 + 1, nullptr, 0);
memcpy(&display_buffer.db[0], &_displaybuffer[i * SH1106_COLUMNS + SH1106_COLUMNS/2 ], SH1106_COLUMNS/2);
_dev->transfer((uint8_t *)&display_buffer, SH1106_COLUMNS/2 + 1, nullptr, 0);
dev.transfer((uint8_t *)&display_buffer, SH1106_COLUMNS/2 + 1, nullptr, 0);
}
}

Expand Down
10 changes: 6 additions & 4 deletions libraries/AP_Notify/Display_SH1106_I2C.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ class Display_SH1106_I2C: public Display_Backend {

public:

static Display_SH1106_I2C *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev);
static Display_Backend *probe(AP_HAL::Device &_dev);

void hw_update() override;
void set_pixel(uint16_t x, uint16_t y) override;
Expand All @@ -21,16 +21,18 @@ class Display_SH1106_I2C: public Display_Backend {

protected:

Display_SH1106_I2C(AP_HAL::OwnPtr<AP_HAL::Device> dev);
~Display_SH1106_I2C() override;
Display_SH1106_I2C(AP_HAL::Device &_dev) :
dev{_dev}
{ }
~Display_SH1106_I2C() override {};

private:

bool hw_init() override;

void _timer();

AP_HAL::OwnPtr<AP_HAL::Device> _dev;
AP_HAL::Device &dev;
uint8_t _displaybuffer[SH1106_COLUMNS * SH1106_ROWS_PER_PAGE];
bool _need_hw_update;

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Notify/Display_SSD1306_I2C.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ Display_SSD1306_I2C::~Display_SSD1306_I2C()
}


Display_SSD1306_I2C *Display_SSD1306_I2C::probe(AP_HAL::Device &_dev)
Display_Backend *Display_SSD1306_I2C::probe(AP_HAL::Device &_dev)
{
Display_SSD1306_I2C *driver = NEW_NOTHROW Display_SSD1306_I2C(_dev);
if (!driver || !driver->hw_init()) {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Notify/Display_SSD1306_I2C.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ class Display_SSD1306_I2C: public Display_Backend {

public:

static Display_SSD1306_I2C *probe(AP_HAL::Device &_dev);
static Display_Backend *probe(AP_HAL::Device &_dev);

void hw_update() override;
void set_pixel(uint16_t x, uint16_t y) override;
Expand Down
Loading