Minimize AP_Progmem.h includes

Most of AP_Progmem is already gone so we can stop including it in most
of the places. The only places that need it are the ones using
pgm_read_*() APIs.

In some cases the header needed to be added in the .cpp since it was
removed from the .h to reduce scope. In those cases the headers were
also reordered.
This commit is contained in:
Lucas De Marchi 2015-10-26 10:01:52 -02:00 committed by Randy Mackay
parent a65c98485c
commit 5244559010
56 changed files with 38 additions and 69 deletions

View File

@ -28,7 +28,6 @@
// Libraries
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Menu/AP_Menu.h>
#include <AP_Param/AP_Param.h>

View File

@ -31,7 +31,6 @@
#include <stdio.h>
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>

View File

@ -36,7 +36,6 @@
// Common dependencies
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Menu/AP_Menu.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>

View File

@ -38,7 +38,6 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Menu/AP_Menu.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>

View File

@ -15,7 +15,6 @@
*/
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>
#include <fenv.h>

View File

@ -33,11 +33,13 @@
just need to be able to enter and exit AUTOTUNE mode
*/
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include "AP_AutoTune.h"
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Progmem/AP_Progmem.h>
extern const AP_HAL::HAL& hal;
// time in milliseconds between autotune saves

View File

@ -54,7 +54,6 @@
*
*/
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>

View File

@ -10,7 +10,6 @@
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>

View File

@ -1,6 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL/AP_HAL.h>
#include <AP_Progmem/AP_Progmem.h>
#include "Compass.h"
#include <AP_Vehicle/AP_Vehicle.h>

View File

@ -7,7 +7,6 @@
#define __AP_CURVE_H__
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <AP_HAL/AP_HAL.h>

View File

@ -1,7 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>
#include <AP_HAL/AP_HAL.h>

View File

@ -15,9 +15,11 @@
*/
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_Progmem/AP_Progmem.h>
#include "AP_GPS.h"
extern const AP_HAL::HAL& hal;

View File

@ -19,7 +19,6 @@
#include <AP_HAL/AP_HAL.h>
#include <inttypes.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>

View File

@ -31,7 +31,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <ctype.h>
#include <stdint.h>
#include <stdlib.h>

View File

@ -6,7 +6,6 @@
#include <stdlib.h>
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_GPS/AP_GPS.h>

View File

@ -8,7 +8,6 @@
#include <stdlib.h>
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_GPS/AP_GPS.h>

View File

@ -5,7 +5,6 @@
#include <stdint.h>
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include "AP_HAL_Boards.h"
#include "AP_HAL_Namespace.h"

View File

@ -28,11 +28,14 @@
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE. */
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include "ftoa_engine.h"
#include <stdint.h>
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Progmem/AP_Progmem.h>
#define PGM_INT8(addr) (int8_t)pgm_read_byte((const char *)addr)
#define PGM_UINT32(addr) pgm_read_dword((const uint32_t *)addr)

View File

@ -37,18 +37,18 @@
/* From: Id: printf_p_new.c,v 1.1.1.9 2002/10/15 20:10:28 joerg_wunsch Exp */
/* $Id: vfprintf.c,v 1.18.2.1 2009/04/01 23:12:06 arcanum Exp $ */
#include "print_vprintf.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_Progmem/AP_Progmem.h>
#include <stdarg.h>
#include <string.h>
#include <math.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Progmem/AP_Progmem.h>
#include "ftoa_engine.h"
#include "xtoa_fast.h"
#include "print_vprintf.h"
#define GETBYTE(flag, mask, pnt) ((flag)&(mask)?pgm_read_byte(pnt++):*pnt++)
#define FL_ZFILL 0x01

View File

@ -8,7 +8,6 @@
#include <AP_ADC/AP_ADC.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <math.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h>

View File

@ -9,7 +9,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>

View File

@ -2,7 +2,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>

View File

@ -9,7 +9,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>

View File

@ -7,7 +7,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>

View File

@ -2,7 +2,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>

View File

@ -2,7 +2,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>

View File

@ -5,7 +5,6 @@
// Connect MISO and MOSI pins together (12 and 13 on Flymaple)
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>

View File

@ -2,7 +2,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>

View File

@ -1,7 +1,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>

View File

@ -2,7 +2,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>

View File

@ -9,7 +9,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>

View File

@ -5,7 +5,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>

View File

@ -1,6 +1,5 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>

View File

@ -2,7 +2,6 @@
#include <assert.h>
#include <AP_Progmem/AP_Progmem.h>
#include "AP_InertialSensor.h"
#include <AP_Common/AP_Common.h>

View File

@ -7,7 +7,6 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Progmem/AP_Progmem.h>
#include <Filter/Filter.h>
#include <Filter/LowPassFilter2p.h>
#include <Filter/LowPassFilter.h>

View File

@ -6,7 +6,6 @@
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include <AP_Progmem/AP_Progmem.h>
#include "AP_InertialSensor.h"
#include <Filter/Filter.h>
#include <Filter/LowPassFilter2p.h>

View File

@ -6,7 +6,6 @@
#include <stdint.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Progmem/AP_Progmem.h>
#include <Filter/Filter.h>
#include <Filter/LowPassFilter2p.h>
#include "AP_InertialSensor.h"

View File

@ -6,7 +6,6 @@
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
#include <AP_Progmem/AP_Progmem.h>
#include "AP_InertialSensor.h"
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>

View File

@ -3,7 +3,6 @@
#define __AP_INERTIAL_SENSOR_USER_INTERACT_H__
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
/* Pure virtual interface class */
class AP_InertialSensor_UserInteract {

View File

@ -6,7 +6,6 @@
#include <stdarg.h>
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>

View File

@ -11,7 +11,9 @@
*/
#include "edc.h"
#include <AP_Progmem/AP_Progmem.h>
/* CRC16 implementation acording to CCITT standards */
static const uint16_t crc16tab[256] = {
0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7,
@ -53,4 +55,4 @@ uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc)
for (uint32_t i = 0; i < len; i++)
crc = (crc << 8) ^ (uint16_t) pgm_read_word(&crc16tab[((crc >> 8) ^ *buf++) & 0x00FF]);
return crc;
}
}

View File

@ -20,7 +20,6 @@
#ifndef __EDC_H_
#define __EDC_H_
#include <AP_Progmem/AP_Progmem.h>
#include <stdint.h>

View File

@ -4,7 +4,6 @@
#define __AP_MOTORS_CLASS_H__
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <AP_Notify/AP_Notify.h> // Notify library
#include <RC_Channel/RC_Channel.h> // RC Channel Library

View File

@ -5,7 +5,6 @@
// Libraries
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library

View File

@ -5,7 +5,6 @@
// Libraries
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library

View File

@ -1,7 +1,6 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include "AP_Mount.h"
#include "AP_Mount_Backend.h"

View File

@ -1,6 +1,5 @@
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h>

View File

@ -1,6 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_Progmem/AP_Progmem.h>
#include "OpticalFlow.h"
extern const AP_HAL::HAL& hal;

View File

@ -4,7 +4,6 @@
*/
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <AP_Param/AP_Param.h>
#include <AP_HAL/AP_HAL.h>

View File

@ -24,9 +24,10 @@
/// @brief The AP variable store.
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Progmem/AP_Progmem.h>
#include <StorageManager/StorageManager.h>
#include <math.h>

View File

@ -4,7 +4,6 @@
*/
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h>

View File

@ -19,10 +19,11 @@
* Author: Andrew Tridgell, January 2013
*
*/
#include "AP_Scheduler.h"
#include <AP_HAL/AP_HAL.h>
#include "AP_Scheduler.h"
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
extern const AP_HAL::HAL& hal;

View File

@ -1,21 +1,22 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL/AP_HAL.h>
#include "DataFlash.h"
#include <stdlib.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_Progmem/AP_Progmem.h>
#include "DataFlash.h"
#include "DataFlash_SITL.h"
#include "DataFlash_File.h"
#include "DataFlash_Empty.h"
#include "DataFlash_APM1.h"
#include "DataFlash_APM2.h"
#include "DFMessageWriter.h"
extern const AP_HAL::HAL& hal;

View File

@ -7,7 +7,6 @@
//
#include <AP_Common/AP_Common.h>
#include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>

View File

@ -23,9 +23,11 @@ This provides some support code and variables for MAVLink enabled sketches
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include "GCS_MAVLink.h"
#include "GCS.h"
#include <AP_GPS/AP_GPS.h>
#include <AP_Progmem/AP_Progmem.h>
#include "GCS.h"
#include "GCS_MAVLink.h"
#ifdef MAVLINK_SEPARATE_HELPERS
#include "include/mavlink/v1.0/mavlink_helpers.h"

View File

@ -19,9 +19,10 @@
Management for hal.storage to allow for backwards compatible mapping
of storage offsets to available storage
*/
#include "StorageManager.h"
#include <AP_HAL/AP_HAL.h>
#include "StorageManager.h"
#include <AP_Progmem/AP_Progmem.h>
extern const AP_HAL::HAL& hal;