mirror of https://github.com/ArduPilot/ardupilot
AP_Notify: Display_SSD1306_I2C: Fix after conversion to I2CDevice
- Initialize device on hw_init() method, allowing it not to be present - Add missing lock - Add packed attribute to structs - Move defines to source file
This commit is contained in:
parent
f26692de92
commit
a34a5c1aa3
|
@ -16,14 +16,16 @@
|
||||||
*/
|
*/
|
||||||
#include "Display_SSD1306_I2C.h"
|
#include "Display_SSD1306_I2C.h"
|
||||||
|
|
||||||
|
#include <utility>
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
#include <AP_HAL/I2CDevice.h>
|
||||||
|
|
||||||
|
#define SSD1306_I2C_BUS 2
|
||||||
|
#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();
|
||||||
|
|
||||||
Display_SSD1306_I2C::Display_SSD1306_I2C():
|
|
||||||
_dev(hal.i2c_mgr->get_device(2, SSD1306_I2C_ADDRESS))
|
|
||||||
{
|
|
||||||
}
|
|
||||||
|
|
||||||
bool Display_SSD1306_I2C::hw_init()
|
bool Display_SSD1306_I2C::hw_init()
|
||||||
{
|
{
|
||||||
|
@ -36,8 +38,10 @@ bool Display_SSD1306_I2C::hw_init()
|
||||||
0xD9, 0xF1, 0xDB, 0x40, 0xA4, 0xA6,
|
0xD9, 0xF1, 0xDB, 0x40, 0xA4, 0xA6,
|
||||||
0xAF, 0x21, 0, 127, 0x22, 0, 7 } };
|
0xAF, 0x21, 0, 127, 0x22, 0, 7 } };
|
||||||
|
|
||||||
|
_dev = std::move(hal.i2c_mgr->get_device(SSD1306_I2C_BUS, SSD1306_I2C_ADDR));
|
||||||
|
|
||||||
// take i2c bus sempahore
|
// take i2c bus sempahore
|
||||||
if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
if (!_dev || !_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -55,15 +59,19 @@ bool Display_SSD1306_I2C::hw_init()
|
||||||
|
|
||||||
bool Display_SSD1306_I2C::hw_update()
|
bool Display_SSD1306_I2C::hw_update()
|
||||||
{
|
{
|
||||||
struct {
|
struct PACKED {
|
||||||
uint8_t reg;
|
uint8_t reg;
|
||||||
uint8_t cmd[6];
|
uint8_t cmd[6];
|
||||||
} command = { 0x0, {0x21, 0, 127, 0x22, 0, 7} };
|
} command = { 0x0, {0x21, 0, 127, 0x22, 0, 7} };
|
||||||
|
|
||||||
struct {
|
struct PACKED {
|
||||||
uint8_t reg;
|
uint8_t reg;
|
||||||
uint8_t db[SSD1306_ROWS];
|
uint8_t db[SSD1306_ROWS];
|
||||||
} display_buffer = { 0x40 };
|
} display_buffer = { 0x40, {} };
|
||||||
|
|
||||||
|
if (!_dev || !_dev->get_semaphore()->take(5)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// write buffer to display
|
// write buffer to display
|
||||||
for (uint8_t i = 0; i < (SSD1306_COLUMNS / SSD1306_COLUMNS_PER_PAGE); i++) {
|
for (uint8_t i = 0; i < (SSD1306_COLUMNS / SSD1306_COLUMNS_PER_PAGE); i++) {
|
||||||
|
|
|
@ -4,14 +4,12 @@
|
||||||
#include "Display.h"
|
#include "Display.h"
|
||||||
#include <AP_HAL/I2CDevice.h>
|
#include <AP_HAL/I2CDevice.h>
|
||||||
|
|
||||||
#define SSD1306_I2C_ADDRESS 0x3C // default I2C bus address
|
|
||||||
#define SSD1306_ROWS 128 // display rows
|
#define SSD1306_ROWS 128 // display rows
|
||||||
#define SSD1306_COLUMNS 64 // display columns
|
#define SSD1306_COLUMNS 64 // display columns
|
||||||
#define SSD1306_COLUMNS_PER_PAGE 8
|
#define SSD1306_COLUMNS_PER_PAGE 8
|
||||||
|
|
||||||
class Display_SSD1306_I2C: public Display {
|
class Display_SSD1306_I2C: public Display {
|
||||||
public:
|
public:
|
||||||
Display_SSD1306_I2C();
|
|
||||||
virtual bool hw_init();
|
virtual bool hw_init();
|
||||||
virtual bool hw_update();
|
virtual bool hw_update();
|
||||||
virtual bool set_pixel(uint16_t x, uint16_t y);
|
virtual bool set_pixel(uint16_t x, uint16_t y);
|
||||||
|
|
Loading…
Reference in New Issue