2015-12-22 17:16:19 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
/*
|
|
|
|
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>
|
|
|
|
|
|
|
|
#define SSD1306_I2C_BUS 2
|
|
|
|
#define SSD1306_I2C_ADDR 0x3C // default I2C bus address
|
2015-12-22 17:16:19 -04:00
|
|
|
|
|
|
|
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|
|
|
|
2016-04-18 17:38:28 -03:00
|
|
|
|
2015-12-22 17:16:19 -04:00
|
|
|
bool Display_SSD1306_I2C::hw_init()
|
|
|
|
{
|
2016-04-18 17:38:28 -03:00
|
|
|
struct {
|
|
|
|
uint8_t reg;
|
|
|
|
uint8_t seq[31];
|
|
|
|
} init_seq = { 0x0, {0xAE, 0xD5, 0x80, 0xA8, 0x3F, 0xD3,
|
2015-12-22 17:16:19 -04:00
|
|
|
0x00, 0x40, 0x8D, 0x14, 0x20, 0x00,
|
|
|
|
0xA1, 0xC8, 0xDA, 0x12, 0x81, 0xCF,
|
|
|
|
0xD9, 0xF1, 0xDB, 0x40, 0xA4, 0xA6,
|
2016-04-18 17:38:28 -03:00
|
|
|
0xAF, 0x21, 0, 127, 0x22, 0, 7 } };
|
2015-12-22 17:16:19 -04:00
|
|
|
|
2016-07-12 01:04:14 -03:00
|
|
|
_dev = std::move(hal.i2c_mgr->get_device(SSD1306_I2C_BUS, SSD1306_I2C_ADDR));
|
|
|
|
|
2015-12-22 17:16:19 -04:00
|
|
|
// take i2c bus sempahore
|
2016-07-12 01:04:14 -03:00
|
|
|
if (!_dev || !_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
2015-12-22 17:16:19 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// init display
|
2016-04-18 17:38:28 -03:00
|
|
|
_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
|
|
|
|
|
|
|
// clear display
|
|
|
|
hw_update();
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool Display_SSD1306_I2C::hw_update()
|
|
|
|
{
|
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;
|
|
|
|
uint8_t db[SSD1306_ROWS];
|
2016-07-12 01:04:14 -03:00
|
|
|
} display_buffer = { 0x40, {} };
|
|
|
|
|
|
|
|
if (!_dev || !_dev->get_semaphore()->take(5)) {
|
|
|
|
return false;
|
|
|
|
}
|
2015-12-22 17:16:19 -04:00
|
|
|
|
|
|
|
// write buffer to display
|
|
|
|
for (uint8_t i = 0; i < (SSD1306_COLUMNS / SSD1306_COLUMNS_PER_PAGE); i++) {
|
2016-04-18 17:38:28 -03:00
|
|
|
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);
|
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
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool Display_SSD1306_I2C::set_pixel(uint16_t x, uint16_t y)
|
|
|
|
{
|
|
|
|
// check x, y range
|
|
|
|
if ((x >= SSD1306_ROWS) || (y >= SSD1306_COLUMNS)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// set pixel in buffer
|
|
|
|
_displaybuffer[x + (y / 8 * SSD1306_ROWS)] |= 1 << (y % 8);
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool Display_SSD1306_I2C::clear_pixel(uint16_t x, uint16_t y)
|
|
|
|
{
|
|
|
|
// check x, y range
|
|
|
|
if ((x >= SSD1306_ROWS) || (y >= SSD1306_COLUMNS)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// clear pixel in buffer
|
|
|
|
_displaybuffer[x + (y / 8 * SSD1306_ROWS)] &= ~(1 << (y % 8));
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|