APM:Libraries
Display_SSD1306_I2C.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #include "Display_SSD1306_I2C.h"
16 
17 #include <utility>
18 
19 #include <AP_HAL/AP_HAL.h>
20 #include <AP_HAL/I2CDevice.h>
21 
22 // constructor
24  _dev(std::move(dev))
25 {
26 }
27 
29 {
30 }
31 
32 
34 {
35  Display_SSD1306_I2C *driver = new Display_SSD1306_I2C(std::move(dev));
36  if (!driver || !driver->hw_init()) {
37  delete driver;
38  return nullptr;
39  }
40  return driver;
41 }
42 
44 {
45  struct PACKED {
46  uint8_t reg;
47  uint8_t seq[31];
48  } init_seq = { 0x0, {
49  // LEGEND:
50  // *** is out of sequence for init steps recommended in datasheet
51  // +++ not listed in sequence for init steps recommended in datasheet
52 
53  0xAE, // Display OFF
54  0xD5, 0x80, // *** Set Display Clock Divide Ratio and Oscillator Frequency
55  // Clock Divide Ratio: 0b (== 1)
56  // Oscillator Frequency: 1000b (== +0%)
57  0xA8, 0x3F, // MUX Ratio: 111111b (== 64MUX)
58  0xD3, 0x00, // Display Offset: 0b (== 0)
59  0x40, // Display Start Line: 0b (== 0)
60  0x8D, 0x14, // *** Enable charge pump regulator: 1b (== Enable)
61  0x20, 0x00, // *** Memory Addressing Mode: 00b (== Horizontal Addressing Mode)
62  0xA1, // Segment re-map: 1b (== column address 127 is mapped to SEG0)
63  0xC8, // COM Output Scan Direction: 1b (== remapped mode. Scan from COM[N-1] to COM0)
64  0xDA, 0x12, // COM Pins hardware configuration: 01b (POR)
65  // (== Alternative COM pin configuration + Disable COM Left/Right remap)
66  0x81, 0xCF, // Contrast Control: 0xCF (== 207 decimal, range 0..255)
67  0xD9, 0xF1, // +++ Pre-charge Period: 0xF1 (== 1 DCLK P1 + 15 DCLK P2)
68  0xDB, 0x40, // +++ VCOMH Deselect Level: 100b (INVALID?!) (== ?!)
69  0xA4, // Entire Display ON (ignoring RAM): (== OFF)
70  0xA6, // Normal/Inverse Display: 0b (== Normal)
71  0xAF, // Display ON: 1b (== ON)
72  0x21, 0, 127, // +++ Column Address: (== start:0, end:127)
73  0x22, 0, 7 // +++ Page Address: (== start:0, end:7)
74  } };
75 
77 
78  // take i2c bus semaphore
80  return false;
81  }
82 
83  // init display
84  bool success = _dev->transfer((uint8_t *)&init_seq, sizeof(init_seq), nullptr, 0);
85 
86  // give back i2c semaphore
87  _dev->get_semaphore()->give();
88 
89  if (success) {
90  _need_hw_update = true;
92  }
93 
94  return success;
95 }
96 
98 {
99  _need_hw_update = true;
100 }
101 
103 {
104  if (!_need_hw_update) {
105  return;
106  }
107  _need_hw_update = false;
108 
109  struct PACKED {
110  uint8_t reg;
111  uint8_t cmd[6];
112  } command = { 0x0, {0x21, 0, 127, 0x22, 0, 7} };
113 
114  struct PACKED {
115  uint8_t reg;
116  uint8_t db[SSD1306_COLUMNS/2];
117  } display_buffer = { 0x40, {} };
118 
119  // write buffer to display
120  for (uint8_t i = 0; i < (SSD1306_ROWS / SSD1306_ROWS_PER_PAGE); i++) {
121  command.cmd[4] = i;
122  _dev->transfer((uint8_t *)&command, sizeof(command), nullptr, 0);
123 
124  memcpy(&display_buffer.db[0], &_displaybuffer[i * SSD1306_COLUMNS], SSD1306_COLUMNS/2);
125  _dev->transfer((uint8_t *)&display_buffer, SSD1306_COLUMNS/2 + 1, nullptr, 0);
126 
127  memcpy(&display_buffer.db[0], &_displaybuffer[i * SSD1306_COLUMNS + SSD1306_COLUMNS/2 ], SSD1306_COLUMNS/2);
128  _dev->transfer((uint8_t *)&display_buffer, SSD1306_COLUMNS/2 + 1, nullptr, 0);
129  }
130 }
131 
132 void Display_SSD1306_I2C::set_pixel(uint16_t x, uint16_t y)
133 {
134  // check x, y range
135  if ((x >= SSD1306_COLUMNS) || (y >= SSD1306_ROWS)) {
136  return;
137  }
138  // set pixel in buffer
139  _displaybuffer[x + (y / 8 * SSD1306_COLUMNS)] |= 1 << (y % 8);
140 }
141 
142 void Display_SSD1306_I2C::clear_pixel(uint16_t x, uint16_t y)
143 {
144  // check x, y range
145  if ((x >= SSD1306_COLUMNS) || (y >= SSD1306_ROWS)) {
146  return;
147  }
148  // clear pixel in buffer
149  _displaybuffer[x + (y / 8 * SSD1306_COLUMNS)] &= ~(1 << (y % 8));
150 }
151 
153 {
155 }
static Display_SSD1306_I2C * probe(AP_HAL::OwnPtr< AP_HAL::Device > dev)
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
#define SSD1306_ROWS
virtual AP_HAL::Semaphore * get_semaphore()=0
#define SSD1306_ROWS_PER_PAGE
#define SSD1306_COLUMNS
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
Display_SSD1306_I2C(AP_HAL::OwnPtr< AP_HAL::Device > dev)
AP_HAL::OwnPtr< AP_HAL::Device > _dev
#define x(i)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
void clear_screen() override
virtual bool give()=0
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)=0
void set_pixel(uint16_t x, uint16_t y) override
#define PACKED
Definition: AP_Common.h:28
uint8_t _displaybuffer[SSD1306_COLUMNS *SSD1306_ROWS_PER_PAGE]
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void clear_pixel(uint16_t x, uint16_t y) override