2015-12-22 17:16:19 -04:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
2016-01-29 00:38:21 -04:00
|
|
|
#include "Display_SSD1306_I2C.h"
|
2015-12-22 17:16:19 -04:00
|
|
|
|
2016-07-12 01:04:14 -03:00
|
|
|
#include <utility>
|
|
|
|
|
2015-12-22 17:16:19 -04:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2016-07-12 01:04:14 -03:00
|
|
|
#include <AP_HAL/I2CDevice.h>
|
|
|
|
|
2017-01-20 02:42:53 -04:00
|
|
|
// constructor
|
|
|
|
Display_SSD1306_I2C::Display_SSD1306_I2C(AP_HAL::OwnPtr<AP_HAL::Device> dev) :
|
2017-01-21 01:03:04 -04:00
|
|
|
_dev(std::move(dev))
|
|
|
|
{
|
|
|
|
}
|
2016-04-18 17:38:28 -03:00
|
|
|
|
2017-03-10 21:16:55 -04:00
|
|
|
Display_SSD1306_I2C::~Display_SSD1306_I2C()
|
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
Display_SSD1306_I2C *Display_SSD1306_I2C::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
|
|
|
{
|
|
|
|
Display_SSD1306_I2C *driver = new Display_SSD1306_I2C(std::move(dev));
|
|
|
|
if (!driver || !driver->hw_init()) {
|
|
|
|
delete driver;
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
return driver;
|
|
|
|
}
|
|
|
|
|
2015-12-22 17:16:19 -04:00
|
|
|
bool Display_SSD1306_I2C::hw_init()
|
|
|
|
{
|
2017-01-20 02:43:23 -04:00
|
|
|
struct PACKED {
|
2016-04-18 17:38:28 -03:00
|
|
|
uint8_t reg;
|
|
|
|
uint8_t seq[31];
|
2016-09-30 04:21:28 -03:00
|
|
|
} init_seq = { 0x0, {
|
|
|
|
// LEGEND:
|
|
|
|
// *** is out of sequence for init steps recommended in datasheet
|
|
|
|
// +++ not listed in sequence for init steps recommended in datasheet
|
|
|
|
|
|
|
|
0xAE, // Display OFF
|
|
|
|
0xD5, 0x80, // *** Set Display Clock Divide Ratio and Oscillator Frequency
|
|
|
|
// Clock Divide Ratio: 0b (== 1)
|
|
|
|
// Oscillator Frequency: 1000b (== +0%)
|
|
|
|
0xA8, 0x3F, // MUX Ratio: 111111b (== 64MUX)
|
|
|
|
0xD3, 0x00, // Display Offset: 0b (== 0)
|
|
|
|
0x40, // Display Start Line: 0b (== 0)
|
|
|
|
0x8D, 0x14, // *** Enable charge pump regulator: 1b (== Enable)
|
|
|
|
0x20, 0x00, // *** Memory Addressing Mode: 00b (== Horizontal Addressing Mode)
|
|
|
|
0xA1, // Segment re-map: 1b (== column address 127 is mapped to SEG0)
|
|
|
|
0xC8, // COM Output Scan Direction: 1b (== remapped mode. Scan from COM[N-1] to COM0)
|
|
|
|
0xDA, 0x12, // COM Pins hardware configuration: 01b (POR)
|
|
|
|
// (== Alternative COM pin configuration + Disable COM Left/Right remap)
|
|
|
|
0x81, 0xCF, // Contrast Control: 0xCF (== 207 decimal, range 0..255)
|
|
|
|
0xD9, 0xF1, // +++ Pre-charge Period: 0xF1 (== 1 DCLK P1 + 15 DCLK P2)
|
|
|
|
0xDB, 0x40, // +++ VCOMH Deselect Level: 100b (INVALID?!) (== ?!)
|
|
|
|
0xA4, // Entire Display ON (ignoring RAM): (== OFF)
|
|
|
|
0xA6, // Normal/Inverse Display: 0b (== Normal)
|
|
|
|
0xAF, // Display ON: 1b (== ON)
|
|
|
|
0x21, 0, 127, // +++ Column Address: (== start:0, end:127)
|
|
|
|
0x22, 0, 7 // +++ Page Address: (== start:0, end:7)
|
|
|
|
} };
|
|
|
|
|
|
|
|
memset(_displaybuffer, 0, SSD1306_COLUMNS * SSD1306_ROWS_PER_PAGE);
|
|
|
|
|
|
|
|
// take i2c bus semaphore
|
2020-01-18 17:42:34 -04:00
|
|
|
if (!_dev) {
|
2015-12-22 17:16:19 -04:00
|
|
|
return false;
|
|
|
|
}
|
2020-01-18 17:42:34 -04:00
|
|
|
_dev->get_semaphore()->take_blocking();
|
2015-12-22 17:16:19 -04:00
|
|
|
|
|
|
|
// init display
|
2017-01-19 03:15:24 -04:00
|
|
|
bool success = _dev->transfer((uint8_t *)&init_seq, sizeof(init_seq), nullptr, 0);
|
2015-12-22 17:16:19 -04:00
|
|
|
|
|
|
|
// give back i2c semaphore
|
2016-04-18 17:38:28 -03:00
|
|
|
_dev->get_semaphore()->give();
|
2015-12-22 17:16:19 -04:00
|
|
|
|
2017-01-19 03:15:24 -04:00
|
|
|
if (success) {
|
|
|
|
_need_hw_update = true;
|
|
|
|
_dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&Display_SSD1306_I2C::_timer, void));
|
|
|
|
}
|
2015-12-22 17:16:19 -04:00
|
|
|
|
2017-01-19 03:15:24 -04:00
|
|
|
return success;
|
2015-12-22 17:16:19 -04:00
|
|
|
}
|
|
|
|
|
2017-01-21 00:59:00 -04:00
|
|
|
void Display_SSD1306_I2C::hw_update()
|
2015-12-22 17:16:19 -04:00
|
|
|
{
|
2016-11-04 01:22:01 -03:00
|
|
|
_need_hw_update = true;
|
|
|
|
}
|
|
|
|
|
2017-01-19 03:15:24 -04:00
|
|
|
void Display_SSD1306_I2C::_timer()
|
2016-11-04 01:22:01 -03:00
|
|
|
{
|
|
|
|
if (!_need_hw_update) {
|
2017-01-13 15:26:14 -04:00
|
|
|
return;
|
2016-11-04 01:22:01 -03:00
|
|
|
}
|
|
|
|
_need_hw_update = false;
|
2016-09-30 04:21:28 -03:00
|
|
|
|
2016-07-12 01:04:14 -03:00
|
|
|
struct PACKED {
|
2016-04-18 17:38:28 -03:00
|
|
|
uint8_t reg;
|
|
|
|
uint8_t cmd[6];
|
|
|
|
} command = { 0x0, {0x21, 0, 127, 0x22, 0, 7} };
|
2015-12-22 17:16:19 -04:00
|
|
|
|
2016-07-12 01:04:14 -03:00
|
|
|
struct PACKED {
|
2016-04-18 17:38:28 -03:00
|
|
|
uint8_t reg;
|
2016-09-30 04:21:28 -03:00
|
|
|
uint8_t db[SSD1306_COLUMNS/2];
|
2016-07-12 01:04:14 -03:00
|
|
|
} display_buffer = { 0x40, {} };
|
|
|
|
|
2015-12-22 17:16:19 -04:00
|
|
|
// write buffer to display
|
2016-09-30 04:21:28 -03:00
|
|
|
for (uint8_t i = 0; i < (SSD1306_ROWS / SSD1306_ROWS_PER_PAGE); i++) {
|
2016-04-18 17:38:28 -03:00
|
|
|
command.cmd[4] = i;
|
|
|
|
_dev->transfer((uint8_t *)&command, sizeof(command), nullptr, 0);
|
|
|
|
|
2017-05-01 08:18:20 -03:00
|
|
|
memcpy(&display_buffer.db[0], &_displaybuffer[i * SSD1306_COLUMNS], SSD1306_COLUMNS/2);
|
|
|
|
_dev->transfer((uint8_t *)&display_buffer, SSD1306_COLUMNS/2 + 1, nullptr, 0);
|
2017-01-21 01:03:04 -04:00
|
|
|
|
2017-05-01 08:18:20 -03:00
|
|
|
memcpy(&display_buffer.db[0], &_displaybuffer[i * SSD1306_COLUMNS + SSD1306_COLUMNS/2 ], SSD1306_COLUMNS/2);
|
|
|
|
_dev->transfer((uint8_t *)&display_buffer, SSD1306_COLUMNS/2 + 1, nullptr, 0);
|
2015-12-22 17:16:19 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-01-21 00:59:00 -04:00
|
|
|
void Display_SSD1306_I2C::set_pixel(uint16_t x, uint16_t y)
|
2015-12-22 17:16:19 -04:00
|
|
|
{
|
|
|
|
// check x, y range
|
2016-09-30 04:21:28 -03:00
|
|
|
if ((x >= SSD1306_COLUMNS) || (y >= SSD1306_ROWS)) {
|
2017-01-21 00:59:00 -04:00
|
|
|
return;
|
2015-12-22 17:16:19 -04:00
|
|
|
}
|
|
|
|
// set pixel in buffer
|
2016-09-30 04:21:28 -03:00
|
|
|
_displaybuffer[x + (y / 8 * SSD1306_COLUMNS)] |= 1 << (y % 8);
|
2015-12-22 17:16:19 -04:00
|
|
|
}
|
|
|
|
|
2017-01-21 00:59:00 -04:00
|
|
|
void Display_SSD1306_I2C::clear_pixel(uint16_t x, uint16_t y)
|
2015-12-22 17:16:19 -04:00
|
|
|
{
|
|
|
|
// check x, y range
|
2016-09-30 04:21:28 -03:00
|
|
|
if ((x >= SSD1306_COLUMNS) || (y >= SSD1306_ROWS)) {
|
2017-01-21 00:59:00 -04:00
|
|
|
return;
|
2015-12-22 17:16:19 -04:00
|
|
|
}
|
|
|
|
// clear pixel in buffer
|
2016-09-30 04:21:28 -03:00
|
|
|
_displaybuffer[x + (y / 8 * SSD1306_COLUMNS)] &= ~(1 << (y % 8));
|
2015-12-22 17:16:19 -04:00
|
|
|
}
|
2017-01-21 01:04:06 -04:00
|
|
|
|
2017-01-21 00:59:00 -04:00
|
|
|
void Display_SSD1306_I2C::clear_screen()
|
2016-09-30 04:21:28 -03:00
|
|
|
{
|
|
|
|
memset(_displaybuffer, 0, SSD1306_COLUMNS * SSD1306_ROWS_PER_PAGE);
|
|
|
|
}
|