mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-19 14:23:57 -04:00
AP_Notify: Reduce flash consumption, remove unneeded middleware classes
This commit is contained in:
parent
10533fb249
commit
d0cd37fabb
@ -26,7 +26,6 @@
|
||||
#include "ToneAlarm_Linux.h"
|
||||
#include "ToneAlarm_ChibiOS.h"
|
||||
#include "ToneAlarm_PX4.h"
|
||||
#include "ToshibaLED.h"
|
||||
#include "ToshibaLED_I2C.h"
|
||||
#include "VRBoard_LED.h"
|
||||
#include "DiscreteRGBLed.h"
|
||||
@ -77,12 +76,14 @@ const AP_Param::GroupInfo AP_Notify::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("DISPLAY_TYPE", 3, AP_Notify, _display_type, 0),
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_PX4_V3
|
||||
// @Param: OREO_THEME
|
||||
// @DisplayName: OreoLED Theme
|
||||
// @Description: Enable/Disable Solo Oreo LED driver, 0 to disable, 1 for Aircraft theme, 2 for Rover theme
|
||||
// @Values: 0:Disabled,1:Aircraft,2:Rover
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OREO_THEME", 4, AP_Notify, _oreo_theme, 0),
|
||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4 && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_PX4_V3
|
||||
|
||||
#if !defined(HAL_BUZZER_PIN)
|
||||
// @Param: BUZZ_PIN
|
||||
@ -265,11 +266,6 @@ void AP_Notify::init(bool enable_external_leds)
|
||||
memset(&AP_Notify::flags, 0, sizeof(AP_Notify::flags));
|
||||
memset(&AP_Notify::events, 0, sizeof(AP_Notify::events));
|
||||
|
||||
// clear flight mode string and text buffer
|
||||
memset(_flight_mode_str, 0, sizeof(_flight_mode_str));
|
||||
memset(_send_text, 0, sizeof(_send_text));
|
||||
_send_text_updated_millis = 0;
|
||||
|
||||
AP_Notify::flags.external_leds = enable_external_leds;
|
||||
|
||||
for (uint8_t i = 0; i < _num_devices; i++) {
|
||||
|
@ -27,12 +27,7 @@ class Buzzer: public NotifyDevice
|
||||
{
|
||||
public:
|
||||
/// Constructor
|
||||
Buzzer() :
|
||||
_counter(0),
|
||||
_pattern(NONE),
|
||||
_pattern_counter(0),
|
||||
_arming_buzz_start_ms(0)
|
||||
{}
|
||||
Buzzer() {}
|
||||
|
||||
/// init - initialise the buzzer
|
||||
bool init(void);
|
||||
|
@ -28,7 +28,7 @@ class ExternalLED: public NotifyDevice
|
||||
{
|
||||
public:
|
||||
// constructor
|
||||
ExternalLED() : _counter(0), _counter2(0), _pattern(NONE), _pattern_counter(0) {}
|
||||
ExternalLED() : _pattern(NONE) {}
|
||||
|
||||
// initialise the LED driver
|
||||
bool init(void);
|
||||
|
@ -1,29 +0,0 @@
|
||||
/*
|
||||
NavioLED driver
|
||||
*/
|
||||
|
||||
/*
|
||||
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.
|
||||
|
||||
*/
|
||||
|
||||
#include "NavioLED.h"
|
||||
|
||||
#define NAVIO_LED_BRIGHT 0x0 // full brightness
|
||||
#define NAVIO_LED_MEDIUM 0x7F // medium brightness
|
||||
#define NAVIO_LED_DIM 0x4F // dim brightness
|
||||
#define NAVIO_LED_OFF 0xFF // off
|
||||
|
||||
NavioLED::NavioLED() :
|
||||
RGBLed(NAVIO_LED_OFF, NAVIO_LED_BRIGHT, NAVIO_LED_MEDIUM, NAVIO_LED_DIM)
|
||||
{
|
||||
|
||||
}
|
@ -1,27 +0,0 @@
|
||||
/*
|
||||
* AP_Notify Library.
|
||||
* based upon a prototype library by David "Buzz" Bussenschutt.
|
||||
*/
|
||||
|
||||
/*
|
||||
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/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "RGBLed.h"
|
||||
|
||||
class NavioLED: public RGBLed {
|
||||
public:
|
||||
NavioLED();
|
||||
};
|
@ -19,11 +19,21 @@
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#define NAVIO_LED_BRIGHT 0x0 // full brightness
|
||||
#define NAVIO_LED_MEDIUM 0x7F // medium brightness
|
||||
#define NAVIO_LED_DIM 0x4F // dim brightness
|
||||
#define NAVIO_LED_OFF 0xFF // off
|
||||
|
||||
#define PCA9685_ADDRESS 0x40
|
||||
#define PCA9685_PWM 0x6
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
NavioLED_I2C::NavioLED_I2C() :
|
||||
RGBLed(NAVIO_LED_OFF, NAVIO_LED_BRIGHT, NAVIO_LED_MEDIUM, NAVIO_LED_DIM)
|
||||
{
|
||||
}
|
||||
|
||||
bool NavioLED_I2C::hw_init()
|
||||
{
|
||||
_dev = hal.i2c_mgr->get_device(1, PCA9685_ADDRESS);
|
||||
|
@ -16,11 +16,13 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "NavioLED.h"
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
#include "RGBLed.h"
|
||||
|
||||
class NavioLED_I2C : public NavioLED
|
||||
class NavioLED_I2C : public RGBLed
|
||||
{
|
||||
public:
|
||||
NavioLED_I2C(void);
|
||||
protected:
|
||||
bool hw_init(void) override;
|
||||
bool hw_set_rgb(uint8_t r, uint8_t g, uint8_t b) override;
|
||||
|
@ -44,11 +44,7 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
// constructor
|
||||
OreoLED_PX4::OreoLED_PX4(uint8_t theme): NotifyDevice(),
|
||||
_overall_health(false),
|
||||
_oreoled_fd(-1),
|
||||
_send_required(false),
|
||||
_state_desired_semaphore(false),
|
||||
_pattern_override(0),
|
||||
_oreo_theme(theme)
|
||||
{
|
||||
// initialise desired and sent state
|
||||
|
@ -24,15 +24,6 @@
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
RGBLed::RGBLed(uint8_t led_off, uint8_t led_bright, uint8_t led_medium, uint8_t led_dim):
|
||||
counter(0),
|
||||
step(0),
|
||||
_healthy(false),
|
||||
_red_des(0),
|
||||
_green_des(0),
|
||||
_blue_des(0),
|
||||
_red_curr(0),
|
||||
_green_curr(0),
|
||||
_blue_curr(0),
|
||||
_led_off(led_off),
|
||||
_led_bright(led_bright),
|
||||
_led_medium(led_medium),
|
||||
|
@ -1,31 +0,0 @@
|
||||
/*
|
||||
ToshibaLED driver
|
||||
*/
|
||||
|
||||
/*
|
||||
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/>.
|
||||
*/
|
||||
|
||||
#include "ToshibaLED.h"
|
||||
|
||||
#define TOSHIBA_LED_BRIGHT 0xFF // full brightness
|
||||
#define TOSHIBA_LED_MEDIUM 0x80 // medium brightness
|
||||
#define TOSHIBA_LED_DIM 0x11 // dim
|
||||
#define TOSHIBA_LED_OFF 0x00 // off
|
||||
|
||||
ToshibaLED::ToshibaLED():
|
||||
RGBLed(TOSHIBA_LED_OFF, TOSHIBA_LED_BRIGHT, TOSHIBA_LED_MEDIUM, TOSHIBA_LED_DIM)
|
||||
{
|
||||
|
||||
}
|
@ -1,27 +0,0 @@
|
||||
/*
|
||||
* AP_Notify Library.
|
||||
* based upon a prototype library by David "Buzz" Bussenschutt.
|
||||
*/
|
||||
|
||||
/*
|
||||
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/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "RGBLed.h"
|
||||
|
||||
class ToshibaLED: public RGBLed {
|
||||
public:
|
||||
ToshibaLED();
|
||||
};
|
@ -26,6 +26,11 @@
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define TOSHIBA_LED_BRIGHT 0xFF // full brightness
|
||||
#define TOSHIBA_LED_MEDIUM 0x80 // medium brightness
|
||||
#define TOSHIBA_LED_DIM 0x11 // dim
|
||||
#define TOSHIBA_LED_OFF 0x00 // off
|
||||
|
||||
#define TOSHIBA_LED_I2C_ADDR 0x55 // default I2C bus address
|
||||
|
||||
#define TOSHIBA_LED_PWM0 0x01 // pwm0 register
|
||||
@ -34,7 +39,7 @@ extern const AP_HAL::HAL& hal;
|
||||
#define TOSHIBA_LED_ENABLE 0x04 // enable register
|
||||
|
||||
ToshibaLED_I2C::ToshibaLED_I2C(uint8_t bus)
|
||||
: ToshibaLED()
|
||||
: RGBLed(TOSHIBA_LED_OFF, TOSHIBA_LED_BRIGHT, TOSHIBA_LED_MEDIUM, TOSHIBA_LED_DIM)
|
||||
, _bus(bus)
|
||||
{
|
||||
}
|
||||
|
@ -17,9 +17,9 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
#include "ToshibaLED.h"
|
||||
#include "RGBLed.h"
|
||||
|
||||
class ToshibaLED_I2C : public ToshibaLED
|
||||
class ToshibaLED_I2C : public RGBLed
|
||||
{
|
||||
public:
|
||||
ToshibaLED_I2C(uint8_t bus);
|
||||
|
Loading…
Reference in New Issue
Block a user