mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Notify: Display backend methods become void
We never use the return value so might as well remove it
This commit is contained in:
parent
0b8ebe36dd
commit
80c1433682
@ -13,8 +13,8 @@ class Display_Backend {
|
||||
|
||||
public:
|
||||
virtual bool hw_init() = 0;
|
||||
virtual bool hw_update() = 0;
|
||||
virtual bool set_pixel(uint16_t x, uint16_t y) = 0;
|
||||
virtual bool clear_pixel(uint16_t x, uint16_t y) = 0;
|
||||
virtual bool clear_screen() = 0;
|
||||
virtual void hw_update() = 0;
|
||||
virtual void set_pixel(uint16_t x, uint16_t y) = 0;
|
||||
virtual void clear_pixel(uint16_t x, uint16_t y) = 0;
|
||||
virtual void clear_screen() = 0;
|
||||
};
|
||||
|
@ -71,10 +71,9 @@ bool Display_SH1106_I2C::hw_init()
|
||||
return success;
|
||||
}
|
||||
|
||||
bool Display_SH1106_I2C::hw_update()
|
||||
void Display_SH1106_I2C::hw_update()
|
||||
{
|
||||
_need_hw_update = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
void Display_SH1106_I2C::_timer()
|
||||
@ -109,31 +108,29 @@ void Display_SH1106_I2C::_timer()
|
||||
}
|
||||
}
|
||||
|
||||
bool Display_SH1106_I2C::set_pixel(uint16_t x, uint16_t y)
|
||||
void Display_SH1106_I2C::set_pixel(uint16_t x, uint16_t y)
|
||||
{
|
||||
// check x, y range
|
||||
if ((x >= SH1106_COLUMNS) || (y >= SH1106_ROWS)) {
|
||||
return false;
|
||||
return;
|
||||
}
|
||||
// set pixel in buffer
|
||||
_displaybuffer[x + (y / 8 * SH1106_COLUMNS)] |= 1 << (y % 8);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool Display_SH1106_I2C::clear_pixel(uint16_t x, uint16_t y)
|
||||
void Display_SH1106_I2C::clear_pixel(uint16_t x, uint16_t y)
|
||||
{
|
||||
// check x, y range
|
||||
if ((x >= SH1106_COLUMNS) || (y >= SH1106_ROWS)) {
|
||||
return false;
|
||||
return;
|
||||
}
|
||||
// clear pixel in buffer
|
||||
_displaybuffer[x + (y / 8 * SH1106_COLUMNS)] &= ~(1 << (y % 8));
|
||||
|
||||
return true;
|
||||
}
|
||||
bool Display_SH1106_I2C::clear_screen()
|
||||
void Display_SH1106_I2C::clear_screen()
|
||||
{
|
||||
memset(_displaybuffer, 0, SH1106_COLUMNS * SH1106_ROWS_PER_PAGE);
|
||||
return true;
|
||||
return;
|
||||
}
|
||||
|
@ -14,10 +14,10 @@ public:
|
||||
Display_SH1106_I2C(AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
|
||||
bool hw_init() override;
|
||||
bool hw_update() override;
|
||||
bool set_pixel(uint16_t x, uint16_t y) override;
|
||||
bool clear_pixel(uint16_t x, uint16_t y) override;
|
||||
bool clear_screen() override;
|
||||
void hw_update() override;
|
||||
void set_pixel(uint16_t x, uint16_t y) override;
|
||||
void clear_pixel(uint16_t x, uint16_t y) override;
|
||||
void clear_screen() override;
|
||||
|
||||
private:
|
||||
void _timer();
|
||||
|
@ -79,10 +79,9 @@ bool Display_SSD1306_I2C::hw_init()
|
||||
return success;
|
||||
}
|
||||
|
||||
bool Display_SSD1306_I2C::hw_update()
|
||||
void Display_SSD1306_I2C::hw_update()
|
||||
{
|
||||
_need_hw_update = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
void Display_SSD1306_I2C::_timer()
|
||||
@ -115,31 +114,28 @@ void Display_SSD1306_I2C::_timer()
|
||||
}
|
||||
}
|
||||
|
||||
bool Display_SSD1306_I2C::set_pixel(uint16_t x, uint16_t y)
|
||||
void Display_SSD1306_I2C::set_pixel(uint16_t x, uint16_t y)
|
||||
{
|
||||
// check x, y range
|
||||
if ((x >= SSD1306_COLUMNS) || (y >= SSD1306_ROWS)) {
|
||||
return false;
|
||||
return;
|
||||
}
|
||||
// set pixel in buffer
|
||||
_displaybuffer[x + (y / 8 * SSD1306_COLUMNS)] |= 1 << (y % 8);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool Display_SSD1306_I2C::clear_pixel(uint16_t x, uint16_t y)
|
||||
void Display_SSD1306_I2C::clear_pixel(uint16_t x, uint16_t y)
|
||||
{
|
||||
// check x, y range
|
||||
if ((x >= SSD1306_COLUMNS) || (y >= SSD1306_ROWS)) {
|
||||
return false;
|
||||
return;
|
||||
}
|
||||
// clear pixel in buffer
|
||||
_displaybuffer[x + (y / 8 * SSD1306_COLUMNS)] &= ~(1 << (y % 8));
|
||||
|
||||
return true;
|
||||
}
|
||||
bool Display_SSD1306_I2C::clear_screen()
|
||||
void Display_SSD1306_I2C::clear_screen()
|
||||
{
|
||||
memset(_displaybuffer, 0, SSD1306_COLUMNS * SSD1306_ROWS_PER_PAGE);
|
||||
return true;
|
||||
}
|
||||
|
@ -14,10 +14,10 @@ public:
|
||||
Display_SSD1306_I2C(AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
||||
|
||||
bool hw_init() override;
|
||||
bool hw_update() override;
|
||||
bool set_pixel(uint16_t x, uint16_t y) override;
|
||||
bool clear_pixel(uint16_t x, uint16_t y) override;
|
||||
bool clear_screen() override;
|
||||
void hw_update() override;
|
||||
void set_pixel(uint16_t x, uint16_t y) override;
|
||||
void clear_pixel(uint16_t x, uint16_t y) override;
|
||||
void clear_screen() override;
|
||||
|
||||
private:
|
||||
void _timer();
|
||||
|
Loading…
Reference in New Issue
Block a user