Browse Source

AP_HAL: standardize inclusion of libaries headers

This commit changes the way libraries headers are included in source files:

 - If the header is in the same directory the source belongs to, so the
 notation '#include ""' is used with the path relative to the directory
 containing the source.

 - If the header is outside the directory containing the source, then we use
 the notation '#include <>' with the path relative to libraries folder.

Some of the advantages of such approach:

 - Only one search path for libraries headers.

 - OSs like Windows may have a better lookup time.
mission-4.1.18
Gustavo Jose de Sousa 10 years ago committed by Andrew Tridgell
parent
commit
0456eccca8
  1. 2
      libraries/AP_HAL/Scheduler.h
  2. 2
      libraries/AP_HAL/Semaphores.h
  3. 2
      libraries/AP_HAL/UARTDriver.cpp
  4. 2
      libraries/AP_HAL/Util.cpp
  5. 2
      libraries/AP_HAL/Util.h
  6. 22
      libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp
  7. 64
      libraries/AP_HAL/examples/Printf/Printf.cpp
  8. 66
      libraries/AP_HAL/examples/RCInput/RCInput.cpp
  9. 66
      libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.cpp
  10. 66
      libraries/AP_HAL/examples/RCOutput/RCOutput.cpp
  11. 68
      libraries/AP_HAL/examples/Storage/Storage.cpp
  12. 66
      libraries/AP_HAL/examples/UART_test/UART_test.cpp
  13. 2
      libraries/AP_HAL/utility/BetterStream.h
  14. 2
      libraries/AP_HAL/utility/Print.cpp
  15. 2
      libraries/AP_HAL/utility/Socket.cpp
  16. 2
      libraries/AP_HAL/utility/Socket.h
  17. 4
      libraries/AP_HAL/utility/ftoa_engine.cpp
  18. 2
      libraries/AP_HAL/utility/ftoa_engine.h
  19. 4
      libraries/AP_HAL/utility/print_vprintf.cpp
  20. 2
      libraries/AP_HAL/utility/print_vprintf.h

2
libraries/AP_HAL/Scheduler.h

@ -6,7 +6,7 @@
#include "AP_HAL_Boards.h" #include "AP_HAL_Boards.h"
#include <stdint.h> #include <stdint.h>
#include <AP_Progmem.h> #include <AP_Progmem/AP_Progmem.h>
class AP_HAL::Scheduler { class AP_HAL::Scheduler {
public: public:

2
libraries/AP_HAL/Semaphores.h

@ -2,7 +2,7 @@
#ifndef __AP_HAL_SEMAPHORES_H__ #ifndef __AP_HAL_SEMAPHORES_H__
#define __AP_HAL_SEMAPHORES_H__ #define __AP_HAL_SEMAPHORES_H__
#include <AP_HAL_Namespace.h> #include "AP_HAL_Namespace.h"
#define HAL_SEMAPHORE_BLOCK_FOREVER ((uint32_t) 0xFFFFFFFF) #define HAL_SEMAPHORE_BLOCK_FOREVER ((uint32_t) 0xFFFFFFFF)

2
libraries/AP_HAL/UARTDriver.cpp

@ -14,7 +14,7 @@
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <AP_HAL.h> #include "AP_HAL.h"
#include "utility/print_vprintf.h" #include "utility/print_vprintf.h"
#include "UARTDriver.h" #include "UARTDriver.h"

2
libraries/AP_HAL/Util.cpp

@ -1,4 +1,4 @@
#include <AP_HAL.h> #include "AP_HAL.h"
#include "Util.h" #include "Util.h"
#include "utility/print_vprintf.h" #include "utility/print_vprintf.h"

2
libraries/AP_HAL/Util.h

@ -4,7 +4,7 @@
#include <stdarg.h> #include <stdarg.h>
#include "AP_HAL_Namespace.h" #include "AP_HAL_Namespace.h"
#include <AP_Progmem.h> #include <AP_Progmem/AP_Progmem.h>
class AP_HAL::Util { class AP_HAL::Util {
public: public:

22
libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp

@ -1,15 +1,15 @@
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_Param.h> #include <AP_Param/AP_Param.h>
#include <AP_Progmem.h> #include <AP_Progmem/AP_Progmem.h>
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR.h> #include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <AP_HAL_SITL.h> #include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_PX4.h> #include <AP_HAL_PX4/AP_HAL_PX4.h>
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <StorageManager.h> #include <StorageManager/StorageManager.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;

64
libraries/AP_HAL/examples/Printf/Printf.cpp

@ -1,35 +1,35 @@
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR.h> #include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <AP_HAL_SITL.h> #include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_PX4.h> #include <AP_HAL_PX4/AP_HAL_PX4.h>
#include <AP_HAL_Linux.h> #include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Baro.h> #include <AP_Baro/AP_Baro.h>
#include <AP_ADC.h> #include <AP_ADC/AP_ADC.h>
#include <AP_GPS.h> #include <AP_GPS/AP_GPS.h>
#include <AP_InertialSensor.h> #include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Notify.h> #include <AP_Notify/AP_Notify.h>
#include <DataFlash.h> #include <DataFlash/DataFlash.h>
#include <GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mission.h> #include <AP_Mission/AP_Mission.h>
#include <StorageManager.h> #include <StorageManager/StorageManager.h>
#include <AP_Terrain.h> #include <AP_Terrain/AP_Terrain.h>
#include <AP_Compass.h> #include <AP_Compass/AP_Compass.h>
#include <AP_Declination.h> #include <AP_Declination/AP_Declination.h>
#include <SITL.h> #include <SITL/SITL.h>
#include <Filter.h> #include <Filter/Filter.h>
#include <AP_Param.h> #include <AP_Param/AP_Param.h>
#include <AP_Progmem.h> #include <AP_Progmem/AP_Progmem.h>
#include <AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_Airspeed.h> #include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Vehicle.h> #include <AP_Vehicle/AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h> #include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_NavEKF.h> #include <AP_NavEKF/AP_NavEKF.h>
#include <AP_Rally.h> #include <AP_Rally/AP_Rally.h>
#include <AP_BattMonitor.h> #include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder.h> #include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;

66
libraries/AP_HAL/examples/RCInput/RCInput.cpp

@ -1,40 +1,40 @@
/* /*
simple test of RC input interface simple test of RC input interface
*/ */
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR.h> #include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <AP_HAL_SITL.h> #include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_PX4.h> #include <AP_HAL_PX4/AP_HAL_PX4.h>
#include <AP_HAL_Linux.h> #include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Baro.h> #include <AP_Baro/AP_Baro.h>
#include <AP_ADC.h> #include <AP_ADC/AP_ADC.h>
#include <AP_GPS.h> #include <AP_GPS/AP_GPS.h>
#include <AP_InertialSensor.h> #include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Notify.h> #include <AP_Notify/AP_Notify.h>
#include <DataFlash.h> #include <DataFlash/DataFlash.h>
#include <GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mission.h> #include <AP_Mission/AP_Mission.h>
#include <StorageManager.h> #include <StorageManager/StorageManager.h>
#include <AP_Terrain.h> #include <AP_Terrain/AP_Terrain.h>
#include <AP_Compass.h> #include <AP_Compass/AP_Compass.h>
#include <AP_Declination.h> #include <AP_Declination/AP_Declination.h>
#include <SITL.h> #include <SITL/SITL.h>
#include <Filter.h> #include <Filter/Filter.h>
#include <AP_Param.h> #include <AP_Param/AP_Param.h>
#include <AP_Progmem.h> #include <AP_Progmem/AP_Progmem.h>
#include <AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_Airspeed.h> #include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Vehicle.h> #include <AP_Vehicle/AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h> #include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_NavEKF.h> #include <AP_NavEKF/AP_NavEKF.h>
#include <AP_Rally.h> #include <AP_Rally/AP_Rally.h>
#include <AP_Scheduler.h> #include <AP_Scheduler/AP_Scheduler.h>
#include <UARTDriver.h> #include <UARTDriver.h>
#include <AP_BattMonitor.h> #include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder.h> #include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;

66
libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.cpp

@ -4,40 +4,40 @@
Max update rate 10 Hz Max update rate 10 Hz
*/ */
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR.h> #include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <AP_HAL_SITL.h> #include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_PX4.h> #include <AP_HAL_PX4/AP_HAL_PX4.h>
#include <AP_HAL_Linux.h> #include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Baro.h> #include <AP_Baro/AP_Baro.h>
#include <AP_ADC.h> #include <AP_ADC/AP_ADC.h>
#include <AP_GPS.h> #include <AP_GPS/AP_GPS.h>
#include <AP_InertialSensor.h> #include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Notify.h> #include <AP_Notify/AP_Notify.h>
#include <DataFlash.h> #include <DataFlash/DataFlash.h>
#include <GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mission.h> #include <AP_Mission/AP_Mission.h>
#include <StorageManager.h> #include <StorageManager/StorageManager.h>
#include <AP_Terrain.h> #include <AP_Terrain/AP_Terrain.h>
#include <AP_Compass.h> #include <AP_Compass/AP_Compass.h>
#include <AP_Declination.h> #include <AP_Declination/AP_Declination.h>
#include <SITL.h> #include <SITL/SITL.h>
#include <Filter.h> #include <Filter/Filter.h>
#include <AP_Param.h> #include <AP_Param/AP_Param.h>
#include <AP_Progmem.h> #include <AP_Progmem/AP_Progmem.h>
#include <AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_Airspeed.h> #include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Vehicle.h> #include <AP_Vehicle/AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h> #include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_NavEKF.h> #include <AP_NavEKF/AP_NavEKF.h>
#include <AP_Rally.h> #include <AP_Rally/AP_Rally.h>
#include <AP_Scheduler.h> #include <AP_Scheduler/AP_Scheduler.h>
#include <UARTDriver.h> #include <UARTDriver.h>
#include <AP_BattMonitor.h> #include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder.h> #include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;

66
libraries/AP_HAL/examples/RCOutput/RCOutput.cpp

@ -1,40 +1,40 @@
/* /*
simple test of RC output interface simple test of RC output interface
*/ */
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR.h> #include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <AP_HAL_SITL.h> #include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_PX4.h> #include <AP_HAL_PX4/AP_HAL_PX4.h>
#include <AP_HAL_Linux.h> #include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Baro.h> #include <AP_Baro/AP_Baro.h>
#include <AP_ADC.h> #include <AP_ADC/AP_ADC.h>
#include <AP_GPS.h> #include <AP_GPS/AP_GPS.h>
#include <AP_InertialSensor.h> #include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Notify.h> #include <AP_Notify/AP_Notify.h>
#include <DataFlash.h> #include <DataFlash/DataFlash.h>
#include <GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mission.h> #include <AP_Mission/AP_Mission.h>
#include <StorageManager.h> #include <StorageManager/StorageManager.h>
#include <AP_Terrain.h> #include <AP_Terrain/AP_Terrain.h>
#include <AP_Compass.h> #include <AP_Compass/AP_Compass.h>
#include <AP_Declination.h> #include <AP_Declination/AP_Declination.h>
#include <SITL.h> #include <SITL/SITL.h>
#include <Filter.h> #include <Filter/Filter.h>
#include <AP_Param.h> #include <AP_Param/AP_Param.h>
#include <AP_Progmem.h> #include <AP_Progmem/AP_Progmem.h>
#include <AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_Airspeed.h> #include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Vehicle.h> #include <AP_Vehicle/AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h> #include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_NavEKF.h> #include <AP_NavEKF/AP_NavEKF.h>
#include <AP_Rally.h> #include <AP_Rally/AP_Rally.h>
#include <AP_Scheduler.h> #include <AP_Scheduler/AP_Scheduler.h>
#include <UARTDriver.h> #include <UARTDriver.h>
#include <AP_BattMonitor.h> #include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder.h> #include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;

68
libraries/AP_HAL/examples/Storage/Storage.cpp

@ -1,41 +1,41 @@
/* /*
simple test of Storage API simple test of Storage API
*/ */
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR.h> #include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <AP_HAL_SITL.h> #include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_PX4.h> #include <AP_HAL_PX4/AP_HAL_PX4.h>
#include <AP_HAL_Linux.h> #include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Baro.h> #include <AP_Baro/AP_Baro.h>
#include <AP_ADC.h> #include <AP_ADC/AP_ADC.h>
#include <AP_GPS.h> #include <AP_GPS/AP_GPS.h>
#include <AP_InertialSensor.h> #include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Notify.h> #include <AP_Notify/AP_Notify.h>
#include <DataFlash.h> #include <DataFlash/DataFlash.h>
#include <GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mission.h> #include <AP_Mission/AP_Mission.h>
#include <StorageManager.h> #include <StorageManager/StorageManager.h>
#include <AP_Terrain.h> #include <AP_Terrain/AP_Terrain.h>
#include <AP_Compass.h> #include <AP_Compass/AP_Compass.h>
#include <AP_Declination.h> #include <AP_Declination/AP_Declination.h>
#include <SITL.h> #include <SITL/SITL.h>
#include <Filter.h> #include <Filter/Filter.h>
#include <AP_Param.h> #include <AP_Param/AP_Param.h>
#include <AP_Progmem.h> #include <AP_Progmem/AP_Progmem.h>
#include <AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_Airspeed.h> #include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Vehicle.h> #include <AP_Vehicle/AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h> #include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_NavEKF.h> #include <AP_NavEKF/AP_NavEKF.h>
#include <AP_Rally.h> #include <AP_Rally/AP_Rally.h>
#include <AP_Scheduler.h> #include <AP_Scheduler/AP_Scheduler.h>
#include <UARTDriver.h> #include <UARTDriver.h>
#include <AP_BattMonitor.h> #include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder.h> #include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_HAL_Boards.h> #include <AP_HAL/AP_HAL_Boards.h>
#if HAL_OS_POSIX_IO #if HAL_OS_POSIX_IO
#include <stdio.h> #include <stdio.h>

66
libraries/AP_HAL/examples/UART_test/UART_test.cpp

@ -1,40 +1,40 @@
/* /*
simple test of UART interfaces simple test of UART interfaces
*/ */
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR.h> #include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <AP_HAL_SITL.h> #include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_PX4.h> #include <AP_HAL_PX4/AP_HAL_PX4.h>
#include <AP_HAL_Linux.h> #include <AP_HAL_Linux/AP_HAL_Linux.h>
#include <AP_HAL_Empty.h> #include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Baro.h> #include <AP_Baro/AP_Baro.h>
#include <AP_ADC.h> #include <AP_ADC/AP_ADC.h>
#include <AP_GPS.h> #include <AP_GPS/AP_GPS.h>
#include <AP_InertialSensor.h> #include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Notify.h> #include <AP_Notify/AP_Notify.h>
#include <DataFlash.h> #include <DataFlash/DataFlash.h>
#include <GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mission.h> #include <AP_Mission/AP_Mission.h>
#include <StorageManager.h> #include <StorageManager/StorageManager.h>
#include <AP_Terrain.h> #include <AP_Terrain/AP_Terrain.h>
#include <AP_Compass.h> #include <AP_Compass/AP_Compass.h>
#include <AP_Declination.h> #include <AP_Declination/AP_Declination.h>
#include <SITL.h> #include <SITL/SITL.h>
#include <Filter.h> #include <Filter/Filter.h>
#include <AP_Param.h> #include <AP_Param/AP_Param.h>
#include <AP_Progmem.h> #include <AP_Progmem/AP_Progmem.h>
#include <AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AP_AHRS.h> #include <AP_AHRS/AP_AHRS.h>
#include <AP_Airspeed.h> #include <AP_Airspeed/AP_Airspeed.h>
#include <AP_Vehicle.h> #include <AP_Vehicle/AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h> #include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_NavEKF.h> #include <AP_NavEKF/AP_NavEKF.h>
#include <AP_Rally.h> #include <AP_Rally/AP_Rally.h>
#include <AP_Scheduler.h> #include <AP_Scheduler/AP_Scheduler.h>
#include <UARTDriver.h> #include <UARTDriver.h>
#include <AP_BattMonitor.h> #include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder.h> #include <AP_RangeFinder/AP_RangeFinder.h>
#if HAL_OS_POSIX_IO #if HAL_OS_POSIX_IO
#include <stdio.h> #include <stdio.h>

2
libraries/AP_HAL/utility/BetterStream.h

@ -26,7 +26,7 @@
#include "Stream.h" #include "Stream.h"
/* prog_char_t: */ /* prog_char_t: */
#include <AP_Progmem.h> #include <AP_Progmem/AP_Progmem.h>
/* AP_HAL::BetterStream is a pure virtual interface. It resembles /* AP_HAL::BetterStream is a pure virtual interface. It resembles
* Michael Smith's BetterStream library for Arduino. * Michael Smith's BetterStream library for Arduino.

2
libraries/AP_HAL/utility/Print.cpp

@ -24,7 +24,7 @@
#include <string.h> #include <string.h>
#include <stdint.h> #include <stdint.h>
#include <AP_Math.h> #include <AP_Math/AP_Math.h>
#include "../AP_HAL_Namespace.h" #include "../AP_HAL_Namespace.h"
#include "Print.h" #include "Print.h"
using namespace AP_HAL; using namespace AP_HAL;

2
libraries/AP_HAL/utility/Socket.cpp

@ -16,7 +16,7 @@
simple socket handling class for systems with BSD socket API simple socket handling class for systems with BSD socket API
*/ */
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#if HAL_OS_SOCKETS #if HAL_OS_SOCKETS
#include "Socket.h" #include "Socket.h"

2
libraries/AP_HAL/utility/Socket.h

@ -19,7 +19,7 @@
#ifndef HAL_SOCKET_H #ifndef HAL_SOCKET_H
#define HAL_SOCKET_H #define HAL_SOCKET_H
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#if HAL_OS_SOCKETS #if HAL_OS_SOCKETS
#include <fcntl.h> #include <fcntl.h>

4
libraries/AP_HAL/utility/ftoa_engine.cpp

@ -28,8 +28,8 @@
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE. */ POSSIBILITY OF SUCH DAMAGE. */
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Common.h> #include <AP_Common/AP_Common.h>
#include "ftoa_engine.h" #include "ftoa_engine.h"
#include <stdint.h> #include <stdint.h>

2
libraries/AP_HAL/utility/ftoa_engine.h

@ -31,7 +31,7 @@
#ifndef _FTOA_ENGINE_H #ifndef _FTOA_ENGINE_H
#define _FTOA_ENGINE_H #define _FTOA_ENGINE_H
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <stdint.h> #include <stdint.h>
int16_t ftoa_engine(float val, char *buf, int16_t ftoa_engine(float val, char *buf,

4
libraries/AP_HAL/utility/print_vprintf.cpp

@ -38,8 +38,8 @@
/* $Id: vfprintf.c,v 1.18.2.1 2009/04/01 23:12:06 arcanum Exp $ */ /* $Id: vfprintf.c,v 1.18.2.1 2009/04/01 23:12:06 arcanum Exp $ */
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Progmem.h> #include <AP_Progmem/AP_Progmem.h>
#include <stdarg.h> #include <stdarg.h>
#include <string.h> #include <string.h>
#include <math.h> #include <math.h>

2
libraries/AP_HAL/utility/print_vprintf.h

@ -2,7 +2,7 @@
#ifndef __AP_HAL_UTILITY_VPRINTF_H__ #ifndef __AP_HAL_UTILITY_VPRINTF_H__
#define __AP_HAL_UTILITY_VPRINTF_H__ #define __AP_HAL_UTILITY_VPRINTF_H__
#include <AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <stdarg.h> #include <stdarg.h>
void print_vprintf (AP_HAL::Print *s, unsigned char in_progmem, const char *fmt, va_list ap); void print_vprintf (AP_HAL::Print *s, unsigned char in_progmem, const char *fmt, va_list ap);

Loading…
Cancel
Save