Skip to content

Commit

Permalink
f4by ssd1306 onboard i2c display support
Browse files Browse the repository at this point in the history
  • Loading branch information
kozinalexey authored and dipspb committed Oct 27, 2016
1 parent 6864864 commit 05c15cf
Show file tree
Hide file tree
Showing 2 changed files with 25 additions and 5 deletions.
9 changes: 9 additions & 0 deletions libraries/AP_Notify/AP_Notify.cpp
Expand Up @@ -86,6 +86,15 @@ struct AP_Notify::notify_events_type AP_Notify::events;
NotifyDevice *AP_Notify::_devices[] = {&boardled, &toshibaled, &tonealarm};
#endif


#elif CONFIG_HAL_BOARD == HAL_BOARD_F4BY
AP_BoardLED boardled;
ToshibaLED_PX4 toshibaled;
ToneAlarm_PX4 tonealarm;
Display_SSD1306_I2C display;
NotifyDevice *AP_Notify::_devices[] = {&boardled, &toshibaled, &tonealarm, &display};


#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
ToneAlarm_PX4 tonealarm;
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_VRBRAIN_V45
Expand Down
21 changes: 16 additions & 5 deletions libraries/AP_Notify/Display_SSD1306_I2C.cpp
Expand Up @@ -18,8 +18,11 @@

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

#if CONFIG_HAL_BOARD == HAL_BOARD_F4BY
#define SSD1306_I2C_BUS 1
#else
#define SSD1306_I2C_BUS 2
#endif
#define SSD1306_I2C_ADDR 0x3C // default I2C bus address

static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
Expand All @@ -36,7 +39,11 @@ bool Display_SSD1306_I2C::hw_init()
0xD9, 0xF1, 0xDB, 0x40, 0xA4, 0xA6,
0xAF, 0x21, 0, 127, 0x22, 0, 7 } };




_dev = std::move(hal.i2c_mgr->get_device(SSD1306_I2C_BUS, SSD1306_I2C_ADDR));
//memset(_displaybuffer, 0, SSD1306_ROWS * SSD1306_COLUMNS_PER_PAGE);

// take i2c bus sempahore
if (!_dev || !_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
Expand Down Expand Up @@ -64,21 +71,25 @@ bool Display_SSD1306_I2C::hw_update()

struct PACKED {
uint8_t reg;
uint8_t db[SSD1306_ROWS];
uint8_t db[SSD1306_ROWS/2];
} display_buffer = { 0x40, {} };


if (!_dev || !_dev->get_semaphore()->take(5)) {
return false;
}

// write buffer to display
for (uint8_t i = 0; i < (SSD1306_COLUMNS / SSD1306_COLUMNS_PER_PAGE); i++) {
command.cmd[4] = i;

_dev->transfer((uint8_t *)&command, sizeof(command), nullptr, 0);

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

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

}

// give back i2c semaphore
Expand Down

0 comments on commit 05c15cf

Please sign in to comment.