AP_Notify: sanitize includes

Due to the way the headers are organized changing a single change in
an AP_Notify driver would trigger a rebuild for most of the files in
the project. Time could be saved by using ccache (since most of the
things didn't change) but we can do better, i.e. re-organize the headers
so we don't have to re-build everything.
This commit is contained in:
Lucas De Marchi 2016-01-29 02:38:21 -02:00
parent 0e09975fa6
commit 5ba20b1763
26 changed files with 60 additions and 90 deletions

View File

@ -14,6 +14,7 @@
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 "AP_BoardLED.h"
#include "AP_Notify.h"

View File

@ -14,12 +14,11 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __AP_HAL_BOARDLED_H__
#define __AP_HAL_BOARDLED_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include "NotifyDevice.h"
#define HIGH 1
@ -38,5 +37,3 @@ private:
// counter incremented at 50Hz
uint8_t _counter;
};
#endif // __AP_HAL_BOARDLED_H__

View File

@ -16,6 +16,20 @@
#include "AP_Notify.h"
#include "AP_BoardLED.h"
#include "Buzzer.h"
#include "Display_SSD1306_I2C.h"
#include "ExternalLED.h"
#include "NavioLED_I2C.h"
#include "OreoLED_PX4.h"
#include "RCOutputRGBLed.h"
#include "ToneAlarm_Linux.h"
#include "ToneAlarm_PX4.h"
#include "ToshibaLED.h"
#include "ToshibaLED_I2C.h"
#include "ToshibaLED_PX4.h"
#include "VRBoard_LED.h"
// table of user settable parameters
const AP_Param::GroupInfo AP_Notify::var_info[] = {

View File

@ -14,27 +14,13 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __AP_NOTIFY_H__
#define __AP_NOTIFY_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Param/AP_Param.h>
#include "AP_BoardLED.h"
#include "ToshibaLED.h"
#include "ToshibaLED_I2C.h"
#include "ToshibaLED_PX4.h"
#include "ToneAlarm_PX4.h"
#include "ToneAlarm_Linux.h"
#include "NavioLED_I2C.h"
#include "ExternalLED.h"
#include "Buzzer.h"
#include "VRBoard_LED.h"
#include "OreoLED_PX4.h"
#include "RCOutputRGBLed.h"
#include "Display.h"
#include "Display_SSD1306_I2C.h"
#include <GCS_MAVLink/GCS_MAVLink.h>
#include "NotifyDevice.h"
#ifndef OREOLED_ENABLED
# define OREOLED_ENABLED 0 // set to 1 to enable OreoLEDs
@ -115,5 +101,3 @@ private:
AP_Int8 _rgb_led_brightness;
};
#endif // __AP_NOTIFY_H__

View File

@ -15,10 +15,10 @@
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 "Buzzer.h"
#include <AP_HAL/AP_HAL.h>
#include "Buzzer.h"
#include "AP_Notify.h"
extern const AP_HAL::HAL& hal;

View File

@ -15,8 +15,7 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __BUZZER_H__
#define __BUZZER_H__
#pragma once
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
# define BUZZER_PIN 32
@ -77,5 +76,3 @@ private:
uint8_t _pattern_counter; // used to time on/off of current patter
uint32_t _arming_buzz_start_ms; // arming_buzz start time in milliseconds
};
#endif // __BUZZER_H__

View File

@ -16,10 +16,11 @@
*/
/* Notify display driver for 128 x 64 pixel displays */
#include "Display.h"
#include "AP_Notify.h"
#include <AP_GPS/AP_GPS.h>
#include "Display.h"
static const uint8_t _font[] = {
0x00, 0x00, 0x00, 0x00, 0x00,

View File

@ -1,5 +1,4 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#pragma once
#include "NotifyDevice.h"

View File

@ -14,11 +14,10 @@
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 "Display_SSD1306_I2C.h"
#include <AP_HAL/AP_HAL.h>
#include "Display_SSD1306_I2C.h"
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
bool Display_SSD1306_I2C::hw_init()

View File

@ -1,5 +1,4 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#pragma once
#include "Display.h"

View File

@ -14,9 +14,11 @@
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 "ExternalLED.h"
#include "AP_Notify.h"
#include <AP_HAL/AP_HAL.h>
#include "AP_Notify.h"
#if (defined(EXTERNAL_LED_ARMED) && defined(EXTERNAL_LED_GPS) && \
defined(EXTERNAL_LED_MOTOR1) && defined(EXTERNAL_LED_MOTOR2))

View File

@ -15,12 +15,12 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __EXTERNALLED_H__
#define __EXTERNALLED_H__
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
#include "NotifyDevice.h"
class ExternalLED: public NotifyDevice
@ -31,7 +31,7 @@ public:
// initialise the LED driver
bool init(void);
// should be called at 50Hz
void update(void);
@ -70,5 +70,3 @@ private:
void motor_led1(bool on_off);
void motor_led2(bool on_off);
};
#endif // __EXTERNALLED_H__

View File

@ -15,9 +15,9 @@
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 "NavioLED_I2C.h"
#include <AP_HAL/AP_HAL.h>
#include "NavioLED_I2C.h"
#define PCA9685_ADDRESS 0x40
#define PCA9685_PWM 0x6

View File

@ -14,8 +14,7 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __NAVIO_LED_I2C_H__
#define __NAVIO_LED_I2C_H__
#pragma once
#include "NavioLED.h"
@ -25,5 +24,3 @@ protected:
virtual bool hw_init(void);
virtual bool hw_set_rgb(uint8_t r, uint8_t g, uint8_t b);
};
#endif // __TOSHIBA_LED_I2C_H__

View File

@ -20,7 +20,6 @@
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
#include "OreoLED_PX4.h"
#include "AP_Notify.h"
#include <sys/types.h>
#include <sys/stat.h>
@ -32,6 +31,8 @@
#include <stdio.h>
#include <errno.h>
#include "AP_Notify.h"
extern const AP_HAL::HAL& hal;
#define OREOLED_BACKLEFT 0 // back left led instance number

View File

@ -14,8 +14,7 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __OREOLED_PX4_H__
#define __OREOLED_PX4_H__
#pragma once
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
@ -93,5 +92,3 @@ private:
};
#endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4
#endif // __OREOLED_PX4_H__

View File

@ -20,16 +20,17 @@
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include "ToneAlarm_Linux.h"
#include "AP_Notify.h"
#include <sys/types.h>
#include <sys/stat.h>
#include <errno.h>
#include <fcntl.h>
#include <stdio.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <unistd.h>
#include <AP_HAL_Linux/Util.h>
#include <stdio.h>
#include <errno.h>
#include "AP_Notify.h"
extern const AP_HAL::HAL& hal;

View File

@ -15,8 +15,7 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __TONE_ALARM_Linux_H__
#define __TONE_ALARM_Linux_H__
#pragma once
#include "NotifyDevice.h"
@ -42,5 +41,3 @@ private:
bool parachute_release : 1; // true if parachute is being released
} flags;
};
#endif // __TONE_ALARM_Linux_H__

View File

@ -15,8 +15,7 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __TONE_ALARM_PX4_H__
#define __TONE_ALARM_PX4_H__
#pragma once
#include "NotifyDevice.h"
@ -69,5 +68,3 @@ private:
const static Tone _tones[];
};
#endif // __TONE_ALARM_PX4_H__

View File

@ -1,5 +1,5 @@
/*
* AP_Notify Library.
* AP_Notify Library.
* based upon a prototype library by David "Buzz" Bussenschutt.
*/
@ -17,9 +17,7 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __TOSHIBA_LED_H__
#define __TOSHIBA_LED_H__
#pragma once
#include "RGBLed.h"
@ -27,5 +25,3 @@ class ToshibaLED: public RGBLed {
public:
ToshibaLED();
};
#endif // __TOSHIBA_LED_H__

View File

@ -15,10 +15,9 @@
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_I2C.h"
#include <AP_HAL/AP_HAL.h>
#include "ToshibaLED.h"
#include "ToshibaLED_I2C.h"
extern const AP_HAL::HAL& hal;

View File

@ -14,8 +14,9 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __TOSHIBA_LED_I2C_H__
#define __TOSHIBA_LED_I2C_H__
#pragma once
#include "ToshibaLED.h"
class ToshibaLED_I2C : public ToshibaLED
{
@ -23,5 +24,3 @@ public:
bool hw_init(void);
bool hw_set_rgb(uint8_t r, uint8_t g, uint8_t b);
};
#endif // __TOSHIBA_LED_I2C_H__

View File

@ -15,13 +15,13 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __TOSHIBA_LED_PX4_H__
#define __TOSHIBA_LED_PX4_H__
#pragma once
#include "ToshibaLED.h"
#include <AP_Math/AP_Math.h>
#include <AP_Math/vectorN.h>
#include "ToshibaLED.h"
class ToshibaLED_PX4 : public ToshibaLED
{
public:
@ -44,5 +44,3 @@ private:
union rgb_value last, next;
};
#endif // __TOSHIBA_LED_PX4_H__

View File

@ -16,8 +16,8 @@
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 "VRBoard_LED.h"
#include <AP_HAL/AP_HAL.h>
#if (defined(HAL_GPIO_A_LED_PIN) && defined(HAL_GPIO_B_LED_PIN) && \

View File

@ -1,5 +1,5 @@
/*
* AP_Notify Library.
* AP_Notify Library.
* based upon a prototype library by David "Buzz" Bussenschutt.
*/
@ -18,13 +18,11 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __VRBRAIN_LED_H__
#define __VRBRAIN_LED_H__
#pragma once
#include "RGBLed.h"
#include "AP_BoardLED.h"
class VRBoard_LED: public RGBLed {
public:
VRBoard_LED();
@ -32,5 +30,3 @@ public:
bool hw_init(void);
bool hw_set_rgb(uint8_t r, uint8_t g, uint8_t b);
};
#endif

View File

@ -1,14 +1,15 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
#include <AP_HAL/AP_HAL.h>
#include <AP_Notify/AP_Notify.h> // Notify library
#include <AP_Notify/ToshibaLED.h>
#include <AP_Notify/AP_Notify.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
#include <AP_Notify/ToshibaLED_PX4.h>
static ToshibaLED_PX4 toshiba_led;
#else
#include <AP_Notify/ToshibaLED_I2C.h>
static ToshibaLED_I2C toshiba_led;
#endif