Browse Source

AP_HAL: make code not depend on concrete HAL implementations

The switching between different AP_HAL was happening by giving different
definitions of AP_HAL_BOARD_DRIVER, and the programs would use it to
instantiate.

A program or library code would have to explicitly include (and depend)
on the concrete implementation of the HAL, even when using it only via
interface.

The proposed change move this dependency to be link time. There is a
AP_HAL::get_HAL() function that is used by the client code. Each
implementation of HAL provides its own definition of this function,
returning the appropriate concrete instance.

Since this replaces the job of AP_HAL_BOARD_DRIVER, the definition was
removed.

The static variables for PX4 and VRBRAIN were named differently to avoid
shadowing the extern symbol 'hal'.
mission-4.1.18
Caio Marcelo de Oliveira Filho 9 years ago committed by Andrew Tridgell
parent
commit
2e464a53c2
  1. 2
      APMrover2/APMrover2.cpp
  2. 2
      AntennaTracker/AntennaTracker.cpp
  3. 2
      ArduCopter/Copter.cpp
  4. 2
      ArduPlane/Plane.cpp
  5. 2
      Tools/CPUInfo/CPUInfo.cpp
  6. 2
      Tools/Hello/Hello.cpp
  7. 2
      Tools/Replay/Replay.cpp
  8. 2
      libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp
  9. 2
      libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.cpp
  10. 2
      libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp
  11. 2
      libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp
  12. 2
      libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp
  13. 2
      libraries/AP_BattMonitor/examples/AP_BattMonitor_test/AP_BattMonitor_test.cpp
  14. 2
      libraries/AP_Common/examples/AP_Common/AP_Common.cpp
  15. 2
      libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp
  16. 2
      libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.cpp
  17. 2
      libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp
  18. 2
      libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp
  19. 14
      libraries/AP_HAL/AP_HAL_Boards.h
  20. 2
      libraries/AP_HAL/AP_HAL_Namespace.h
  21. 2
      libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp
  22. 2
      libraries/AP_HAL/examples/Printf/Printf.cpp
  23. 2
      libraries/AP_HAL/examples/RCInput/RCInput.cpp
  24. 2
      libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.cpp
  25. 2
      libraries/AP_HAL/examples/RCOutput/RCOutput.cpp
  26. 2
      libraries/AP_HAL/examples/Storage/Storage.cpp
  27. 2
      libraries/AP_HAL/examples/UART_test/UART_test.cpp
  28. 5
      libraries/AP_HAL_AVR/HAL_AVR_APM1_Class.cpp
  29. 5
      libraries/AP_HAL_AVR/HAL_AVR_APM2_Class.cpp
  30. 2
      libraries/AP_HAL_AVR/examples/Semaphore/Semaphore.cpp
  31. 2
      libraries/AP_HAL_AVR/examples/UtilityStringTest/UtilityStringTest.cpp
  32. 5
      libraries/AP_HAL_Empty/HAL_Empty_Class.cpp
  33. 2
      libraries/AP_HAL_Empty/examples/empty_example/empty_example.cpp
  34. 5
      libraries/AP_HAL_FLYMAPLE/HAL_FLYMAPLE_Class.cpp
  35. 2
      libraries/AP_HAL_FLYMAPLE/examples/AP_Baro_BMP085_test/AP_Baro_BMP085_test.cpp
  36. 2
      libraries/AP_HAL_FLYMAPLE/examples/AnalogIn/AnalogIn.cpp
  37. 2
      libraries/AP_HAL_FLYMAPLE/examples/Blink/Blink.cpp
  38. 2
      libraries/AP_HAL_FLYMAPLE/examples/Console/Console.cpp
  39. 2
      libraries/AP_HAL_FLYMAPLE/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.cpp
  40. 2
      libraries/AP_HAL_FLYMAPLE/examples/RCInput/RCInput.cpp
  41. 2
      libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/RCPassthroughTest.cpp
  42. 2
      libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/SPIDriver.cpp
  43. 2
      libraries/AP_HAL_FLYMAPLE/examples/Scheduler/Scheduler.cpp
  44. 2
      libraries/AP_HAL_FLYMAPLE/examples/Semaphore/Semaphore.cpp
  45. 2
      libraries/AP_HAL_FLYMAPLE/examples/Storage/Storage.cpp
  46. 2
      libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/UARTDriver.cpp
  47. 2
      libraries/AP_HAL_FLYMAPLE/examples/UtilityStringTest/UtilityStringTest.cpp
  48. 2
      libraries/AP_HAL_FLYMAPLE/examples/empty_example/empty_example.cpp
  49. 4
      libraries/AP_HAL_Linux/GPIO.cpp
  50. 2
      libraries/AP_HAL_Linux/GPIO_BBB.cpp
  51. 4
      libraries/AP_HAL_Linux/GPIO_RPI.cpp
  52. 5
      libraries/AP_HAL_Linux/HAL_Linux_Class.cpp
  53. 2
      libraries/AP_HAL_Linux/RCInput_Raspilot.cpp
  54. 2
      libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp
  55. 2
      libraries/AP_HAL_Linux/RCOutput_Bebop.cpp
  56. 2
      libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp
  57. 2
      libraries/AP_HAL_Linux/RCOutput_PRU.cpp
  58. 2
      libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp
  59. 2
      libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp
  60. 2
      libraries/AP_HAL_Linux/examples/BusTest/BusTest.cpp
  61. 5
      libraries/AP_HAL_PX4/HAL_PX4_Class.cpp
  62. 2
      libraries/AP_HAL_PX4/examples/simple/simple.cpp
  63. 5
      libraries/AP_HAL_SITL/HAL_SITL_Class.cpp
  64. 5
      libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp
  65. 2
      libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp
  66. 4
      libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp
  67. 2
      libraries/AP_Math/examples/eulers/eulers.cpp
  68. 2
      libraries/AP_Math/examples/location/location.cpp
  69. 2
      libraries/AP_Math/examples/polygon/polygon.cpp
  70. 2
      libraries/AP_Math/examples/rotations/rotations.cpp
  71. 2
      libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp
  72. 2
      libraries/AP_Motors/examples/AP_Motors_Time_test/AP_Motors_Time_test.cpp
  73. 2
      libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp
  74. 2
      libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.cpp
  75. 2
      libraries/AP_Notify/examples/AP_Notify_test/AP_Notify_test.cpp
  76. 2
      libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp
  77. 2
      libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp
  78. 2
      libraries/AP_Parachute/examples/AP_Parachute_test/AP_Parachute_test.cpp
  79. 2
      libraries/AP_PerfMon/AP_PerfMon_test/AP_PerfMon_test.cpp
  80. 2
      libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp
  81. 2
      libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp
  82. 2
      libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp
  83. 2
      libraries/Filter/examples/Derivative/Derivative.cpp
  84. 2
      libraries/Filter/examples/Filter/Filter.cpp
  85. 2
      libraries/Filter/examples/LowPassFilter/LowPassFilter.cpp
  86. 2
      libraries/Filter/examples/LowPassFilter2p/LowPassFilter2p.cpp
  87. 2
      libraries/GCS_Console/examples/Console/Console.cpp
  88. 2
      libraries/GCS_MAVLink/examples/routing/routing.cpp
  89. 2
      libraries/PID/examples/pid/pid.cpp
  90. 2
      libraries/RC_Channel/examples/RC_Channel/RC_Channel.cpp
  91. 2
      libraries/StorageManager/examples/StorageTest/StorageTest.cpp

2
APMrover2/APMrover2.cpp

@ -33,7 +33,7 @@ @@ -33,7 +33,7 @@
#include "Rover.h"
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
Rover rover;

2
AntennaTracker/AntennaTracker.cpp

@ -117,7 +117,7 @@ void Tracker::one_second_loop() @@ -117,7 +117,7 @@ void Tracker::one_second_loop()
AP_ADC_ADS7844 apm1_adc;
#endif
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
Tracker::Tracker(void)
{

2
ArduCopter/Copter.cpp

@ -19,7 +19,7 @@ @@ -19,7 +19,7 @@
constructor for main Copter class
*/
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
Copter::Copter(void) :
ins_sample_rate(AP_InertialSensor::RATE_400HZ),

2
ArduPlane/Plane.cpp

@ -20,7 +20,7 @@ @@ -20,7 +20,7 @@
constructor for main Plane class
*/
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
Plane::Plane(void)
{

2
Tools/CPUInfo/CPUInfo.cpp

@ -39,7 +39,7 @@ @@ -39,7 +39,7 @@
#include <AP_OpticalFlow/AP_OpticalFlow.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup() {
}

2
Tools/Hello/Hello.cpp

@ -30,7 +30,7 @@ @@ -30,7 +30,7 @@
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
#include <AP_Notify/AP_Notify.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup() {
hal.console->println_P(PSTR("hello world"));

2
Tools/Replay/Replay.cpp

@ -72,7 +72,7 @@ @@ -72,7 +72,7 @@
#define streq(x, y) (!strcmp(x, y))
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
class ReplayVehicle {
public:

2
libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp

@ -38,7 +38,7 @@ @@ -38,7 +38,7 @@
#include <AP_Rally/AP_Rally.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// default PID values
#define TEST_P 1.0f

2
libraries/AP_ADC/examples/AP_ADC_test/AP_ADC_test.cpp

@ -22,7 +22,7 @@ uint32_t timer; @@ -22,7 +22,7 @@ uint32_t timer;
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
/* Only build this sketch for APM1 and Linux */
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_ADC_ADS7844 adc;

2
libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp

@ -43,7 +43,7 @@ @@ -43,7 +43,7 @@
#include <RC_Channel/RC_Channel.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// INS and Baro declaration
AP_InertialSensor ins;

2
libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp

@ -55,7 +55,7 @@ @@ -55,7 +55,7 @@
AP_ADC_ADS7844 apm1_adc;
#endif
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_Vehicle::FixedWing aparm;

2
libraries/AP_Baro/examples/BARO_generic/BARO_generic.cpp

@ -36,7 +36,7 @@ @@ -36,7 +36,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_Baro barometer;

2
libraries/AP_BattMonitor/examples/AP_BattMonitor_test/AP_BattMonitor_test.cpp

@ -33,7 +33,7 @@ @@ -33,7 +33,7 @@
#include <AP_Terrain/AP_Terrain.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_BattMonitor battery_mon;
uint32_t timer;

2
libraries/AP_Common/examples/AP_Common/AP_Common.cpp

@ -15,7 +15,7 @@ @@ -15,7 +15,7 @@
#include <AP_Math/AP_Math.h>
#include <StorageManager/StorageManager.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void test_high_low_byte(void)
{

2
libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.cpp

@ -38,7 +38,7 @@ @@ -38,7 +38,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static Compass compass;

2
libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.cpp

@ -12,7 +12,7 @@ @@ -12,7 +12,7 @@
#include <AP_HAL_AVR/AP_HAL_AVR.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static const int16_t dec_tbl[37][73] = \
{ \

2
libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp

@ -40,7 +40,7 @@ @@ -40,7 +40,7 @@
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// create board led object
AP_BoardLED board_led;

2
libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp

@ -39,7 +39,7 @@ @@ -39,7 +39,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup()
{

14
libraries/AP_HAL/AP_HAL_Boards.h

@ -117,14 +117,7 @@ @@ -117,14 +117,7 @@
*/
/*
define AP_HAL_BOARD_DRIVER to the right hal type for this
board. This prevents us having a mess of ifdefs in every example
sketch
*/
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
#define AP_HAL_BOARD_DRIVER AP_HAL_AVR_APM1
#define HAL_BOARD_NAME "APM 1"
#define HAL_CPU_CLASS HAL_CPU_CLASS_16
#define HAL_STORAGE_SIZE 4096
@ -137,7 +130,6 @@ @@ -137,7 +130,6 @@
#endif
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
#define AP_HAL_BOARD_DRIVER AP_HAL_AVR_APM2
#define HAL_BOARD_NAME "APM 2"
#define HAL_CPU_CLASS HAL_CPU_CLASS_16
#define HAL_STORAGE_SIZE 4096
@ -154,7 +146,6 @@ @@ -154,7 +146,6 @@
#endif
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
#define AP_HAL_BOARD_DRIVER AP_HAL_SITL
#define HAL_BOARD_NAME "SITL"
#define HAL_CPU_CLASS HAL_CPU_CLASS_1000
#define HAL_OS_POSIX_IO 1
@ -169,7 +160,6 @@ @@ -169,7 +160,6 @@
#define HAL_COMPASS_DEFAULT HAL_COMPASS_HIL
#elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
#define AP_HAL_BOARD_DRIVER AP_HAL_FLYMAPLE
#define HAL_BOARD_NAME "FLYMAPLE"
#define HAL_CPU_CLASS HAL_CPU_CLASS_75
#define HAL_STORAGE_SIZE 4096
@ -181,7 +171,6 @@ @@ -181,7 +171,6 @@
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
#define AP_HAL_BOARD_DRIVER AP_HAL_PX4
#define HAL_BOARD_NAME "PX4"
#define HAL_CPU_CLASS HAL_CPU_CLASS_150
#define HAL_OS_POSIX_IO 1
@ -201,7 +190,6 @@ @@ -201,7 +190,6 @@
#endif
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#define AP_HAL_BOARD_DRIVER AP_HAL_Linux
#define HAL_BOARD_NAME "Linux"
#define HAL_CPU_CLASS HAL_CPU_CLASS_1000
#define HAL_OS_POSIX_IO 1
@ -270,7 +258,6 @@ @@ -270,7 +258,6 @@
#endif
#elif CONFIG_HAL_BOARD == HAL_BOARD_EMPTY
#define AP_HAL_BOARD_DRIVER AP_HAL_Empty
#define HAL_BOARD_NAME "EMPTY"
#define HAL_CPU_CLASS HAL_CPU_CLASS_16
#define HAL_STORAGE_SIZE 4096
@ -281,7 +268,6 @@ @@ -281,7 +268,6 @@
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
#define AP_HAL_BOARD_DRIVER AP_HAL_VRBRAIN
#define HAL_BOARD_NAME "VRBRAIN"
#define HAL_CPU_CLASS HAL_CPU_CLASS_150
#define HAL_OS_POSIX_IO 1

2
libraries/AP_HAL/AP_HAL_Namespace.h

@ -62,6 +62,8 @@ namespace AP_HAL { @@ -62,6 +62,8 @@ namespace AP_HAL {
SPIDevice_RASPIO = 12
};
// Must be implemented by the concrete HALs.
const HAL& get_HAL();
}
#endif // __AP_HAL_NAMESPACE_H__

2
libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp

@ -11,7 +11,7 @@ @@ -11,7 +11,7 @@
#include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <StorageManager/StorageManager.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_HAL::AnalogSource* ch;

2
libraries/AP_HAL/examples/Printf/Printf.cpp

@ -31,7 +31,7 @@ @@ -31,7 +31,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup(void) {
hal.console->println_P(PSTR("Starting Printf test"));

2
libraries/AP_HAL/examples/RCInput/RCInput.cpp

@ -36,7 +36,7 @@ @@ -36,7 +36,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#define MAX_CHANNELS 16

2
libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.cpp

@ -39,7 +39,7 @@ @@ -39,7 +39,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#define MAX_CHANNELS 14

2
libraries/AP_HAL/examples/RCOutput/RCOutput.cpp

@ -36,7 +36,7 @@ @@ -36,7 +36,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup (void)
{

2
libraries/AP_HAL/examples/Storage/Storage.cpp

@ -41,7 +41,7 @@ @@ -41,7 +41,7 @@
#include <stdio.h>
#endif
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_HAL::Storage *st;

2
libraries/AP_HAL/examples/UART_test/UART_test.cpp

@ -40,7 +40,7 @@ @@ -40,7 +40,7 @@
#include <stdio.h>
#endif
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_HAL::UARTDriver* uarts[] = {
hal.uartA, // console

5
libraries/AP_HAL_AVR/HAL_AVR_APM1_Class.cpp

@ -86,6 +86,9 @@ void HAL_AVR_APM1::init(int argc, char * const argv[]) const { @@ -86,6 +86,9 @@ void HAL_AVR_APM1::init(int argc, char * const argv[]) const {
PORTJ |= _BV(0);
};
const HAL_AVR_APM1 AP_HAL_AVR_APM1;
const AP_HAL::HAL& AP_HAL::get_HAL() {
static const HAL_AVR_APM1 hal;
return hal;
}
#endif // CONFIG_HAL_BOARD == HAL_BOARD_APM1

5
libraries/AP_HAL_AVR/HAL_AVR_APM2_Class.cpp

@ -85,6 +85,9 @@ void HAL_AVR_APM2::init(int argc, char * const argv[]) const { @@ -85,6 +85,9 @@ void HAL_AVR_APM2::init(int argc, char * const argv[]) const {
PORTH |= _BV(0);
};
const HAL_AVR_APM2 AP_HAL_AVR_APM2;
const AP_HAL::HAL& AP_HAL::get_HAL() {
static const HAL_AVR_APM2 hal;
return hal;
}
#endif // CONFIG_HAL_BOARD == HAL_BOARD_APM2

2
libraries/AP_HAL_AVR/examples/Semaphore/Semaphore.cpp

@ -6,7 +6,7 @@ @@ -6,7 +6,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR/AP_HAL_AVR.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
/**
* You'll want to use a logic analyzer to watch the effects of this test.

2
libraries/AP_HAL_AVR/examples/UtilityStringTest/UtilityStringTest.cpp

@ -11,7 +11,7 @@ @@ -11,7 +11,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_AVR/AP_HAL_AVR.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void test_snprintf_P() {
char test[40];

5
libraries/AP_HAL_Empty/HAL_Empty_Class.cpp

@ -52,6 +52,9 @@ void HAL_Empty::init(int argc,char* const argv[]) const { @@ -52,6 +52,9 @@ void HAL_Empty::init(int argc,char* const argv[]) const {
_member->init();
}
const HAL_Empty AP_HAL_Empty;
const AP_HAL::HAL& AP_HAL::get_HAL() {
static const HAL_Empty hal;
return hal;
}
#endif

2
libraries/AP_HAL_Empty/examples/empty_example/empty_example.cpp

@ -10,7 +10,7 @@ @@ -10,7 +10,7 @@
#include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_Empty/AP_HAL_Empty.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup() {
hal.console->println_P(PSTR("Empty setup"));

5
libraries/AP_HAL_FLYMAPLE/HAL_FLYMAPLE_Class.cpp

@ -85,6 +85,9 @@ void HAL_FLYMAPLE::init(int argc,char* const argv[]) const { @@ -85,6 +85,9 @@ void HAL_FLYMAPLE::init(int argc,char* const argv[]) const {
storage->init(NULL); // Uses EEPROM.*, flash_stm* copied from AeroQuad_v3.2
}
const HAL_FLYMAPLE AP_HAL_FLYMAPLE;
const AP_HAL::HAL& AP_HAL::get_HAL() {
static const HAL_FLYMAPLE hal;
return hal;
}
#endif

2
libraries/AP_HAL_FLYMAPLE/examples/AP_Baro_BMP085_test/AP_Baro_BMP085_test.cpp

@ -24,7 +24,7 @@ @@ -24,7 +24,7 @@
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_Baro_BMP085 bmp085;

2
libraries/AP_HAL_FLYMAPLE/examples/AnalogIn/AnalogIn.cpp

@ -14,7 +14,7 @@ @@ -14,7 +14,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// Expects pin 15 to be connected to board VCC 3.3V
static AP_HAL::AnalogSource *vcc_pin; // GPIO pin 15

2
libraries/AP_HAL_FLYMAPLE/examples/Blink/Blink.cpp

@ -7,7 +7,7 @@ @@ -7,7 +7,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_HAL::DigitalSource *a_led;
AP_HAL::DigitalSource *b_led;

2
libraries/AP_HAL_FLYMAPLE/examples/Console/Console.cpp

@ -15,7 +15,7 @@ @@ -15,7 +15,7 @@
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup(void)
{

2
libraries/AP_HAL_FLYMAPLE/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.cpp

@ -12,7 +12,7 @@ @@ -12,7 +12,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#define HMC5883L 0x1E

2
libraries/AP_HAL_FLYMAPLE/examples/RCInput/RCInput.cpp

@ -7,7 +7,7 @@ @@ -7,7 +7,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
/* Multi-channel read method: */

2
libraries/AP_HAL_FLYMAPLE/examples/RCPassthroughTest/RCPassthroughTest.cpp

@ -7,7 +7,7 @@ @@ -7,7 +7,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
/* Multi-channel read method: */

2
libraries/AP_HAL_FLYMAPLE/examples/SPIDriver/SPIDriver.cpp

@ -10,7 +10,7 @@ @@ -10,7 +10,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_HAL::SPIDeviceDriver* spidev;

2
libraries/AP_HAL_FLYMAPLE/examples/Scheduler/Scheduler.cpp

@ -7,7 +7,7 @@ @@ -7,7 +7,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
/**
* You'll want to use a logic analyzer to watch the effects of this test.

2
libraries/AP_HAL_FLYMAPLE/examples/Semaphore/Semaphore.cpp

@ -6,7 +6,7 @@ @@ -6,7 +6,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
/**
* You'll want to use a logic analyzer to watch the effects of this test.

2
libraries/AP_HAL_FLYMAPLE/examples/Storage/Storage.cpp

@ -7,7 +7,7 @@ @@ -7,7 +7,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
uint8_t fibs[] = { 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55, 89, 144, 0 };

2
libraries/AP_HAL_FLYMAPLE/examples/UARTDriver/UARTDriver.cpp

@ -14,7 +14,7 @@ @@ -14,7 +14,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup(void)
{

2
libraries/AP_HAL_FLYMAPLE/examples/UtilityStringTest/UtilityStringTest.cpp

@ -10,7 +10,7 @@ @@ -10,7 +10,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void test_snprintf_P() {
char test[40];

2
libraries/AP_HAL_FLYMAPLE/examples/empty_example/empty_example.cpp

@ -6,7 +6,7 @@ @@ -6,7 +6,7 @@
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup() {
hal.scheduler->delay(5000);

4
libraries/AP_HAL_Linux/GPIO.cpp

@ -5,7 +5,7 @@ @@ -5,7 +5,7 @@
using namespace Linux;
static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
LinuxDigitalSource::LinuxDigitalSource(uint8_t v) :
_v(v)
@ -33,4 +33,4 @@ void LinuxDigitalSource::toggle() @@ -33,4 +33,4 @@ void LinuxDigitalSource::toggle()
write(!read());
}
#endif
#endif

2
libraries/AP_HAL_Linux/GPIO_BBB.cpp

@ -17,7 +17,7 @@ @@ -17,7 +17,7 @@
using namespace Linux;
static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
LinuxGPIO_BBB::LinuxGPIO_BBB()
{}

4
libraries/AP_HAL_Linux/GPIO_RPI.cpp

@ -18,7 +18,7 @@ @@ -18,7 +18,7 @@
using namespace Linux;
static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
LinuxGPIO_RPI::LinuxGPIO_RPI()
{}
@ -198,4 +198,4 @@ bool LinuxGPIO_RPI::usb_connected(void) @@ -198,4 +198,4 @@ bool LinuxGPIO_RPI::usb_connected(void)
return false;
}
#endif // CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
#endif // CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT

5
libraries/AP_HAL_Linux/HAL_Linux_Class.cpp

@ -236,6 +236,9 @@ void HAL_Linux::init(int argc,char* const argv[]) const @@ -236,6 +236,9 @@ void HAL_Linux::init(int argc,char* const argv[]) const
utilInstance.init(argc+gopt.optind-1, &argv[gopt.optind-1]);
}
const HAL_Linux AP_HAL_Linux;
const AP_HAL::HAL& AP_HAL::get_HAL() {
static const HAL_Linux hal;
return hal;
}
#endif

2
libraries/AP_HAL_Linux/RCInput_Raspilot.cpp

@ -15,7 +15,7 @@ @@ -15,7 +15,7 @@
#include "px4io_protocol.h"
static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
using namespace Linux;

2
libraries/AP_HAL_Linux/RCOutput_AioPRU.cpp

@ -27,7 +27,7 @@ @@ -27,7 +27,7 @@
using namespace Linux;
static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static void catch_sigbus(int sig)
{

2
libraries/AP_HAL_Linux/RCOutput_Bebop.cpp

@ -89,7 +89,7 @@ enum { @@ -89,7 +89,7 @@ enum {
using namespace Linux;
static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
LinuxRCOutput_Bebop::LinuxRCOutput_Bebop():
_i2c_sem(NULL),

2
libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp

@ -54,7 +54,7 @@ using namespace Linux; @@ -54,7 +54,7 @@ using namespace Linux;
#define PWM_CHAN_COUNT 16
static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
LinuxRCOutput_PCA9685::LinuxRCOutput_PCA9685(uint8_t addr,
bool external_clock,

2
libraries/AP_HAL_Linux/RCOutput_PRU.cpp

@ -24,7 +24,7 @@ using namespace Linux; @@ -24,7 +24,7 @@ using namespace Linux;
static const uint8_t chan_pru_map[]= {10,8,11,9,7,6,5,4,3,2,1,0}; //chan_pru_map[CHANNEL_NUM] = PRU_REG_R30/31_NUM;
static const uint8_t pru_chan_map[]= {11,10,9,8,7,6,5,4,1,3,0,2}; //pru_chan_map[PRU_REG_R30/31_NUM] = CHANNEL_NUM;
static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static void catch_sigbus(int sig)
{
hal.scheduler->panic("RCOutput.cpp:SIGBUS error gernerated\n");

2
libraries/AP_HAL_Linux/RCOutput_Raspilot.cpp

@ -20,7 +20,7 @@ using namespace Linux; @@ -20,7 +20,7 @@ using namespace Linux;
#define PWM_CHAN_COUNT 8
static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void LinuxRCOutput_Raspilot::init(void* machtnicht)
{

2
libraries/AP_HAL_Linux/RCOutput_ZYNQ.cpp

@ -20,7 +20,7 @@ using namespace Linux; @@ -20,7 +20,7 @@ using namespace Linux;
#define PWM_CHAN_COUNT 8 // FIXME
static const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static void catch_sigbus(int sig)
{
hal.scheduler->panic("RCOutput.cpp:SIGBUS error gernerated\n");

2
libraries/AP_HAL_Linux/examples/BusTest/BusTest.cpp

@ -13,7 +13,7 @@ @@ -13,7 +13,7 @@
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup(void)
{

5
libraries/AP_HAL_PX4/HAL_PX4_Class.cpp

@ -307,7 +307,10 @@ void HAL_PX4::init(int argc, char * const argv[]) const @@ -307,7 +307,10 @@ void HAL_PX4::init(int argc, char * const argv[]) const
exit(1);
}
const HAL_PX4 AP_HAL_PX4;
const AP_HAL::HAL& AP_HAL::get_HAL() {
static const HAL_PX4 hal_px4;
return hal_px4;
}
#endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4

2
libraries/AP_HAL_PX4/examples/simple/simple.cpp

@ -39,7 +39,7 @@ @@ -39,7 +39,7 @@
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup() {
hal.console->println_P(PSTR("hello world"));

5
libraries/AP_HAL_SITL/HAL_SITL_Class.cpp

@ -79,6 +79,9 @@ void HAL_SITL::init(int argc, char * const argv[]) const @@ -79,6 +79,9 @@ void HAL_SITL::init(int argc, char * const argv[]) const
analogin->init(NULL);
}
const HAL_SITL AP_HAL_SITL;
const AP_HAL::HAL& AP_HAL::get_HAL() {
static const HAL_SITL hal;
return hal;
}
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL

5
libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp

@ -339,7 +339,10 @@ void HAL_VRBRAIN::init(int argc, char * const argv[]) const @@ -339,7 +339,10 @@ void HAL_VRBRAIN::init(int argc, char * const argv[]) const
exit(1);
}
const HAL_VRBRAIN AP_HAL_VRBRAIN;
const AP_HAL::HAL& AP_HAL::get_HAL() {
static const HAL_VRBRAIN hal_vrbrain;
return hal_vrbrain;
}
#endif // CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN

2
libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp

@ -41,7 +41,7 @@ @@ -41,7 +41,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_InertialSensor ins;

4
libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp

@ -50,7 +50,7 @@ @@ -50,7 +50,7 @@
#include <unistd.h>
#include <stdio.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static int accel_fd[INS_MAX_INSTANCES];
static int gyro_fd[INS_MAX_INSTANCES];
@ -210,7 +210,7 @@ void loop(void) @@ -210,7 +210,7 @@ void loop(void)
}
#else
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup() {}
void loop() {}
#endif // CONFIG_HAL_BOARD

2
libraries/AP_Math/examples/eulers/eulers.cpp

@ -37,7 +37,7 @@ @@ -37,7 +37,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#define SHOW_POLES_BREAKDOWN 0

2
libraries/AP_Math/examples/location/location.cpp

@ -37,7 +37,7 @@ @@ -37,7 +37,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static const struct {
Vector2f wp1, wp2, location;

2
libraries/AP_Math/examples/polygon/polygon.cpp

@ -12,7 +12,7 @@ @@ -12,7 +12,7 @@
#include <AP_HAL_AVR/AP_HAL_AVR.h>
#include <AP_HAL_Linux/AP_HAL_Linux.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
/*
* this is the boundary of the 2010 outback challenge

2
libraries/AP_Math/examples/rotations/rotations.cpp

@ -37,7 +37,7 @@ @@ -37,7 +37,7 @@
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_OpticalFlow/AP_OpticalFlow.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static void print_vector(Vector3f &v)
{

2
libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.cpp

@ -38,7 +38,7 @@ @@ -38,7 +38,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
class MissionTest {
public:

2
libraries/AP_Motors/examples/AP_Motors_Time_test/AP_Motors_Time_test.cpp

@ -37,7 +37,7 @@ @@ -37,7 +37,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
RC_Channel rc1(0), rc2(1), rc3(2), rc4(3);

2
libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp

@ -37,7 +37,7 @@ @@ -37,7 +37,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
RC_Channel rc1(0), rc2(1), rc3(2), rc4(3);

2
libraries/AP_Mount/examples/trivial_AP_Mount/trivial_AP_Mount.cpp

@ -30,7 +30,7 @@ @@ -30,7 +30,7 @@
#include <AP_Mount/AP_Mount.h>
#include <AP_HAL_AVR/AP_HAL_AVR.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup () {
hal.console->println_P(PSTR("Unit test for AP_Mount. This sketch"

2
libraries/AP_Notify/examples/AP_Notify_test/AP_Notify_test.cpp

@ -18,7 +18,7 @@ @@ -18,7 +18,7 @@
#include <StorageManager/StorageManager.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// create board led object
AP_BoardLED board_led;

2
libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp

@ -34,7 +34,7 @@ @@ -34,7 +34,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
static ToshibaLED_PX4 toshiba_led;

2
libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.cpp

@ -30,7 +30,7 @@ @@ -30,7 +30,7 @@
#include <AP_Terrain/AP_Terrain.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static OpticalFlow optflow;

2
libraries/AP_Parachute/examples/AP_Parachute_test/AP_Parachute_test.cpp

@ -15,7 +15,7 @@ @@ -15,7 +15,7 @@
#include <AP_Notify/AP_Notify.h>
#include <StorageManager/StorageManager.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// Relay
AP_Relay relay;

2
libraries/AP_PerfMon/AP_PerfMon_test/AP_PerfMon_test.cpp

@ -12,7 +12,7 @@ @@ -12,7 +12,7 @@
#include <StorageManager/StorageManager.h>
#include <AP_PerfMon/AP_PerfMon.h> // PerfMonitor library
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_PERFMON_REGISTER_FN(setup)
AP_PERFMON_REGISTER_FN(loop)

2
libraries/AP_RangeFinder/examples/RFIND_test/RFIND_test.cpp

@ -36,7 +36,7 @@ @@ -36,7 +36,7 @@
#include <AP_Rally/AP_Rally.h>
#include <AP_SerialManager/AP_SerialManager.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_SerialManager serial_manager;
static RangeFinder sonar {serial_manager};

2
libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp

@ -40,7 +40,7 @@ @@ -40,7 +40,7 @@
#include <AP_HAL_Empty/AP_HAL_Empty.h>
#include <AP_HAL_PX4/AP_HAL_PX4.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
class SchedTest {
public:

2
libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp

@ -39,7 +39,7 @@ @@ -39,7 +39,7 @@
#include <AP_BattMonitor/AP_BattMonitor.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#define LOG_TEST_MSG 1

2
libraries/Filter/examples/Derivative/Derivative.cpp

@ -13,7 +13,7 @@ @@ -13,7 +13,7 @@
#include <Filter/Filter.h>
#include <Filter/DerivativeFilter.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
DerivativeFilter<float,11> derivative;

2
libraries/Filter/examples/Filter/Filter.cpp

@ -16,7 +16,7 @@ @@ -16,7 +16,7 @@
#include <Filter/ModeFilter.h> // ModeFilter class (inherits from Filter class)
#include <Filter/AverageFilter.h> // AverageFilter class (inherits from Filter class)
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
int16_t rangevalue[] = {31000, 31000, 50, 55, 60, 55, 10, 0, 31000};

2
libraries/Filter/examples/LowPassFilter/LowPassFilter.cpp

@ -13,7 +13,7 @@ @@ -13,7 +13,7 @@
#include <Filter/Filter.h> // Filter library
#include <Filter/LowPassFilter.h> // LowPassFilter class (inherits from Filter class)
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// create a global instance of the class
LowPassFilterFloat low_pass_filter;

2
libraries/Filter/examples/LowPassFilter2p/LowPassFilter2p.cpp

@ -15,7 +15,7 @@ @@ -15,7 +15,7 @@
#include <Filter/Filter.h> // Filter library
#include <Filter/LowPassFilter2p.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
// craete an instance with 800Hz sample rate and 30Hz cutoff
static LowPassFilter2pFloat low_pass_filter(800, 30);

2
libraries/GCS_Console/examples/Console/Console.cpp

@ -21,7 +21,7 @@ @@ -21,7 +21,7 @@
#include "simplegcs.h"
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void flush_console_to_statustext() {
uint8_t data[50];

2
libraries/GCS_MAVLink/examples/routing/routing.cpp

@ -43,7 +43,7 @@ @@ -43,7 +43,7 @@
#include <SITL/SITL.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
static GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS];

2
libraries/PID/examples/pid/pid.cpp

@ -15,7 +15,7 @@ @@ -15,7 +15,7 @@
#include <AP_HAL_SITL/AP_HAL_SITL.h>
#include <AP_HAL_Empty/AP_HAL_Empty.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
long radio_in;
long radio_trim;

2
libraries/RC_Channel/examples/RC_Channel/RC_Channel.cpp

@ -46,7 +46,7 @@ @@ -46,7 +46,7 @@
#include <AP_HAL/UARTDriver.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#define NUM_CHANNELS 8

2
libraries/StorageManager/examples/StorageTest/StorageTest.cpp

@ -40,7 +40,7 @@ @@ -40,7 +40,7 @@
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_RangeFinder/AP_RangeFinder.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#define DO_INITIALISATION 1

Loading…
Cancel
Save