mirror of https://github.com/ArduPilot/ardupilot
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'.
This commit is contained in:
parent
79d85f7e10
commit
2e464a53c2
|
@ -33,7 +33,7 @@
|
||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
Rover rover;
|
Rover rover;
|
||||||
|
|
||||||
|
|
|
@ -117,7 +117,7 @@ void Tracker::one_second_loop()
|
||||||
AP_ADC_ADS7844 apm1_adc;
|
AP_ADC_ADS7844 apm1_adc;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
Tracker::Tracker(void)
|
Tracker::Tracker(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -19,7 +19,7 @@
|
||||||
constructor for main Copter class
|
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) :
|
Copter::Copter(void) :
|
||||||
ins_sample_rate(AP_InertialSensor::RATE_400HZ),
|
ins_sample_rate(AP_InertialSensor::RATE_400HZ),
|
||||||
|
|
|
@ -20,7 +20,7 @@
|
||||||
constructor for main Plane class
|
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)
|
Plane::Plane(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -39,7 +39,7 @@
|
||||||
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
}
|
}
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
||||||
#include <AP_Notify/AP_Notify.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() {
|
void setup() {
|
||||||
hal.console->println_P(PSTR("hello world"));
|
hal.console->println_P(PSTR("hello world"));
|
||||||
|
|
|
@ -72,7 +72,7 @@
|
||||||
|
|
||||||
#define streq(x, y) (!strcmp(x, y))
|
#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 {
|
class ReplayVehicle {
|
||||||
public:
|
public:
|
||||||
|
|
|
@ -38,7 +38,7 @@
|
||||||
#include <AP_Rally/AP_Rally.h>
|
#include <AP_Rally/AP_Rally.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
// default PID values
|
// default PID values
|
||||||
#define TEST_P 1.0f
|
#define TEST_P 1.0f
|
||||||
|
|
|
@ -22,7 +22,7 @@ uint32_t timer;
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
/* Only build this sketch for APM1 and 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;
|
AP_ADC_ADS7844 adc;
|
||||||
|
|
||||||
|
|
|
@ -43,7 +43,7 @@
|
||||||
#include <RC_Channel/RC_Channel.h>
|
#include <RC_Channel/RC_Channel.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
// INS and Baro declaration
|
// INS and Baro declaration
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
|
|
@ -55,7 +55,7 @@
|
||||||
AP_ADC_ADS7844 apm1_adc;
|
AP_ADC_ADS7844 apm1_adc;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
static AP_Vehicle::FixedWing aparm;
|
static AP_Vehicle::FixedWing aparm;
|
||||||
|
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
static AP_Baro barometer;
|
static AP_Baro barometer;
|
||||||
|
|
||||||
|
|
|
@ -33,7 +33,7 @@
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
AP_BattMonitor battery_mon;
|
AP_BattMonitor battery_mon;
|
||||||
uint32_t timer;
|
uint32_t timer;
|
||||||
|
|
|
@ -15,7 +15,7 @@
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <StorageManager/StorageManager.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)
|
void test_high_low_byte(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -38,7 +38,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
static Compass compass;
|
static Compass compass;
|
||||||
|
|
||||||
|
|
|
@ -12,7 +12,7 @@
|
||||||
|
|
||||||
#include <AP_HAL_AVR/AP_HAL_AVR.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();
|
||||||
|
|
||||||
static const int16_t dec_tbl[37][73] = \
|
static const int16_t dec_tbl[37][73] = \
|
||||||
{ \
|
{ \
|
||||||
|
|
|
@ -40,7 +40,7 @@
|
||||||
#include <AP_SerialManager/AP_SerialManager.h>
|
#include <AP_SerialManager/AP_SerialManager.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
// create board led object
|
// create board led object
|
||||||
AP_BoardLED board_led;
|
AP_BoardLED board_led;
|
||||||
|
|
|
@ -39,7 +39,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
|
|
|
@ -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
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
#define AP_HAL_BOARD_DRIVER AP_HAL_AVR_APM1
|
|
||||||
#define HAL_BOARD_NAME "APM 1"
|
#define HAL_BOARD_NAME "APM 1"
|
||||||
#define HAL_CPU_CLASS HAL_CPU_CLASS_16
|
#define HAL_CPU_CLASS HAL_CPU_CLASS_16
|
||||||
#define HAL_STORAGE_SIZE 4096
|
#define HAL_STORAGE_SIZE 4096
|
||||||
|
@ -137,7 +130,6 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
#define AP_HAL_BOARD_DRIVER AP_HAL_AVR_APM2
|
|
||||||
#define HAL_BOARD_NAME "APM 2"
|
#define HAL_BOARD_NAME "APM 2"
|
||||||
#define HAL_CPU_CLASS HAL_CPU_CLASS_16
|
#define HAL_CPU_CLASS HAL_CPU_CLASS_16
|
||||||
#define HAL_STORAGE_SIZE 4096
|
#define HAL_STORAGE_SIZE 4096
|
||||||
|
@ -154,7 +146,6 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
#define AP_HAL_BOARD_DRIVER AP_HAL_SITL
|
|
||||||
#define HAL_BOARD_NAME "SITL"
|
#define HAL_BOARD_NAME "SITL"
|
||||||
#define HAL_CPU_CLASS HAL_CPU_CLASS_1000
|
#define HAL_CPU_CLASS HAL_CPU_CLASS_1000
|
||||||
#define HAL_OS_POSIX_IO 1
|
#define HAL_OS_POSIX_IO 1
|
||||||
|
@ -169,7 +160,6 @@
|
||||||
#define HAL_COMPASS_DEFAULT HAL_COMPASS_HIL
|
#define HAL_COMPASS_DEFAULT HAL_COMPASS_HIL
|
||||||
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
|
||||||
#define AP_HAL_BOARD_DRIVER AP_HAL_FLYMAPLE
|
|
||||||
#define HAL_BOARD_NAME "FLYMAPLE"
|
#define HAL_BOARD_NAME "FLYMAPLE"
|
||||||
#define HAL_CPU_CLASS HAL_CPU_CLASS_75
|
#define HAL_CPU_CLASS HAL_CPU_CLASS_75
|
||||||
#define HAL_STORAGE_SIZE 4096
|
#define HAL_STORAGE_SIZE 4096
|
||||||
|
@ -181,7 +171,6 @@
|
||||||
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE
|
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE
|
||||||
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
#define AP_HAL_BOARD_DRIVER AP_HAL_PX4
|
|
||||||
#define HAL_BOARD_NAME "PX4"
|
#define HAL_BOARD_NAME "PX4"
|
||||||
#define HAL_CPU_CLASS HAL_CPU_CLASS_150
|
#define HAL_CPU_CLASS HAL_CPU_CLASS_150
|
||||||
#define HAL_OS_POSIX_IO 1
|
#define HAL_OS_POSIX_IO 1
|
||||||
|
@ -201,7 +190,6 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
#define AP_HAL_BOARD_DRIVER AP_HAL_Linux
|
|
||||||
#define HAL_BOARD_NAME "Linux"
|
#define HAL_BOARD_NAME "Linux"
|
||||||
#define HAL_CPU_CLASS HAL_CPU_CLASS_1000
|
#define HAL_CPU_CLASS HAL_CPU_CLASS_1000
|
||||||
#define HAL_OS_POSIX_IO 1
|
#define HAL_OS_POSIX_IO 1
|
||||||
|
@ -270,7 +258,6 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_EMPTY
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_EMPTY
|
||||||
#define AP_HAL_BOARD_DRIVER AP_HAL_Empty
|
|
||||||
#define HAL_BOARD_NAME "EMPTY"
|
#define HAL_BOARD_NAME "EMPTY"
|
||||||
#define HAL_CPU_CLASS HAL_CPU_CLASS_16
|
#define HAL_CPU_CLASS HAL_CPU_CLASS_16
|
||||||
#define HAL_STORAGE_SIZE 4096
|
#define HAL_STORAGE_SIZE 4096
|
||||||
|
@ -281,7 +268,6 @@
|
||||||
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE
|
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE
|
||||||
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
#define AP_HAL_BOARD_DRIVER AP_HAL_VRBRAIN
|
|
||||||
#define HAL_BOARD_NAME "VRBRAIN"
|
#define HAL_BOARD_NAME "VRBRAIN"
|
||||||
#define HAL_CPU_CLASS HAL_CPU_CLASS_150
|
#define HAL_CPU_CLASS HAL_CPU_CLASS_150
|
||||||
#define HAL_OS_POSIX_IO 1
|
#define HAL_OS_POSIX_IO 1
|
||||||
|
|
|
@ -62,6 +62,8 @@ namespace AP_HAL {
|
||||||
SPIDevice_RASPIO = 12
|
SPIDevice_RASPIO = 12
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// Must be implemented by the concrete HALs.
|
||||||
|
const HAL& get_HAL();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // __AP_HAL_NAMESPACE_H__
|
#endif // __AP_HAL_NAMESPACE_H__
|
||||||
|
|
|
@ -11,7 +11,7 @@
|
||||||
#include <AP_HAL_Empty/AP_HAL_Empty.h>
|
#include <AP_HAL_Empty/AP_HAL_Empty.h>
|
||||||
#include <StorageManager/StorageManager.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;
|
AP_HAL::AnalogSource* ch;
|
||||||
|
|
||||||
|
|
|
@ -31,7 +31,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
void setup(void) {
|
void setup(void) {
|
||||||
hal.console->println_P(PSTR("Starting Printf test"));
|
hal.console->println_P(PSTR("Starting Printf test"));
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
#define MAX_CHANNELS 16
|
#define MAX_CHANNELS 16
|
||||||
|
|
||||||
|
|
|
@ -39,7 +39,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
#define MAX_CHANNELS 14
|
#define MAX_CHANNELS 14
|
||||||
|
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
void setup (void)
|
void setup (void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -41,7 +41,7 @@
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
AP_HAL::Storage *st;
|
AP_HAL::Storage *st;
|
||||||
|
|
||||||
|
|
|
@ -40,7 +40,7 @@
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
static AP_HAL::UARTDriver* uarts[] = {
|
static AP_HAL::UARTDriver* uarts[] = {
|
||||||
hal.uartA, // console
|
hal.uartA, // console
|
||||||
|
|
|
@ -86,6 +86,9 @@ void HAL_AVR_APM1::init(int argc, char * const argv[]) const {
|
||||||
PORTJ |= _BV(0);
|
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
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
|
|
|
@ -85,6 +85,9 @@ void HAL_AVR_APM2::init(int argc, char * const argv[]) const {
|
||||||
PORTH |= _BV(0);
|
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
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
|
|
|
@ -6,7 +6,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_AVR/AP_HAL_AVR.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.
|
* You'll want to use a logic analyzer to watch the effects of this test.
|
||||||
|
|
|
@ -11,7 +11,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_AVR/AP_HAL_AVR.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() {
|
void test_snprintf_P() {
|
||||||
char test[40];
|
char test[40];
|
||||||
|
|
|
@ -52,6 +52,9 @@ void HAL_Empty::init(int argc,char* const argv[]) const {
|
||||||
_member->init();
|
_member->init();
|
||||||
}
|
}
|
||||||
|
|
||||||
const HAL_Empty AP_HAL_Empty;
|
const AP_HAL::HAL& AP_HAL::get_HAL() {
|
||||||
|
static const HAL_Empty hal;
|
||||||
|
return hal;
|
||||||
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
#include <AP_HAL_SITL/AP_HAL_SITL.h>
|
#include <AP_HAL_SITL/AP_HAL_SITL.h>
|
||||||
#include <AP_HAL_Empty/AP_HAL_Empty.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() {
|
void setup() {
|
||||||
hal.console->println_P(PSTR("Empty setup"));
|
hal.console->println_P(PSTR("Empty setup"));
|
||||||
|
|
|
@ -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
|
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
|
#endif
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
|
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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_Baro_BMP085 bmp085;
|
AP_Baro_BMP085 bmp085;
|
||||||
|
|
||||||
|
|
|
@ -14,7 +14,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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
|
// Expects pin 15 to be connected to board VCC 3.3V
|
||||||
static AP_HAL::AnalogSource *vcc_pin; // GPIO pin 15
|
static AP_HAL::AnalogSource *vcc_pin; // GPIO pin 15
|
||||||
|
|
|
@ -7,7 +7,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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 *a_led;
|
||||||
AP_HAL::DigitalSource *b_led;
|
AP_HAL::DigitalSource *b_led;
|
||||||
|
|
|
@ -15,7 +15,7 @@
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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)
|
void setup(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -12,7 +12,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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
|
#define HMC5883L 0x1E
|
||||||
|
|
||||||
|
|
|
@ -7,7 +7,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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) {
|
void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
|
||||||
/* Multi-channel read method: */
|
/* Multi-channel read method: */
|
||||||
|
|
|
@ -7,7 +7,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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) {
|
void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
|
||||||
/* Multi-channel read method: */
|
/* Multi-channel read method: */
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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;
|
AP_HAL::SPIDeviceDriver* spidev;
|
||||||
|
|
||||||
|
|
|
@ -7,7 +7,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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.
|
* You'll want to use a logic analyzer to watch the effects of this test.
|
||||||
|
|
|
@ -6,7 +6,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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.
|
* You'll want to use a logic analyzer to watch the effects of this test.
|
||||||
|
|
|
@ -7,7 +7,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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 };
|
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 };
|
||||||
|
|
||||||
|
|
|
@ -14,7 +14,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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)
|
void setup(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -10,7 +10,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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() {
|
void test_snprintf_P() {
|
||||||
char test[40];
|
char test[40];
|
||||||
|
|
|
@ -6,7 +6,7 @@
|
||||||
|
|
||||||
#include <AP_HAL_FLYMAPLE/AP_HAL_FLYMAPLE.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 setup() {
|
||||||
hal.scheduler->delay(5000);
|
hal.scheduler->delay(5000);
|
||||||
|
|
|
@ -5,7 +5,7 @@
|
||||||
|
|
||||||
using namespace Linux;
|
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) :
|
LinuxDigitalSource::LinuxDigitalSource(uint8_t v) :
|
||||||
_v(v)
|
_v(v)
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
using namespace Linux;
|
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()
|
LinuxGPIO_BBB::LinuxGPIO_BBB()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
|
|
@ -18,7 +18,7 @@
|
||||||
|
|
||||||
using namespace Linux;
|
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()
|
LinuxGPIO_RPI::LinuxGPIO_RPI()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
|
|
@ -236,6 +236,9 @@ void HAL_Linux::init(int argc,char* const argv[]) const
|
||||||
utilInstance.init(argc+gopt.optind-1, &argv[gopt.optind-1]);
|
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
|
#endif
|
||||||
|
|
|
@ -15,7 +15,7 @@
|
||||||
|
|
||||||
#include "px4io_protocol.h"
|
#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;
|
using namespace Linux;
|
||||||
|
|
||||||
|
|
|
@ -27,7 +27,7 @@
|
||||||
|
|
||||||
using namespace Linux;
|
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)
|
static void catch_sigbus(int sig)
|
||||||
{
|
{
|
||||||
|
|
|
@ -89,7 +89,7 @@ enum {
|
||||||
|
|
||||||
using namespace Linux;
|
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():
|
LinuxRCOutput_Bebop::LinuxRCOutput_Bebop():
|
||||||
_i2c_sem(NULL),
|
_i2c_sem(NULL),
|
||||||
|
|
|
@ -54,7 +54,7 @@ using namespace Linux;
|
||||||
|
|
||||||
#define PWM_CHAN_COUNT 16
|
#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,
|
LinuxRCOutput_PCA9685::LinuxRCOutput_PCA9685(uint8_t addr,
|
||||||
bool external_clock,
|
bool external_clock,
|
||||||
|
|
|
@ -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 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 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)
|
static void catch_sigbus(int sig)
|
||||||
{
|
{
|
||||||
hal.scheduler->panic("RCOutput.cpp:SIGBUS error gernerated\n");
|
hal.scheduler->panic("RCOutput.cpp:SIGBUS error gernerated\n");
|
||||||
|
|
|
@ -20,7 +20,7 @@ using namespace Linux;
|
||||||
|
|
||||||
#define PWM_CHAN_COUNT 8
|
#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)
|
void LinuxRCOutput_Raspilot::init(void* machtnicht)
|
||||||
{
|
{
|
||||||
|
|
|
@ -20,7 +20,7 @@ using namespace Linux;
|
||||||
|
|
||||||
#define PWM_CHAN_COUNT 8 // FIXME
|
#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)
|
static void catch_sigbus(int sig)
|
||||||
{
|
{
|
||||||
hal.scheduler->panic("RCOutput.cpp:SIGBUS error gernerated\n");
|
hal.scheduler->panic("RCOutput.cpp:SIGBUS error gernerated\n");
|
||||||
|
|
|
@ -13,7 +13,7 @@
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <StorageManager/StorageManager.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)
|
void setup(void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -307,7 +307,10 @@ void HAL_PX4::init(int argc, char * const argv[]) const
|
||||||
exit(1);
|
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
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
|
|
||||||
|
|
|
@ -39,7 +39,7 @@
|
||||||
#include <AP_Scheduler/AP_Scheduler.h>
|
#include <AP_Scheduler/AP_Scheduler.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
hal.console->println_P(PSTR("hello world"));
|
hal.console->println_P(PSTR("hello world"));
|
||||||
|
|
|
@ -79,6 +79,9 @@ void HAL_SITL::init(int argc, char * const argv[]) const
|
||||||
analogin->init(NULL);
|
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
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
|
|
@ -339,7 +339,10 @@ void HAL_VRBRAIN::init(int argc, char * const argv[]) const
|
||||||
exit(1);
|
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
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
|
|
||||||
|
|
|
@ -41,7 +41,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
|
||||||
|
|
|
@ -50,7 +50,7 @@
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
#include <stdio.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 accel_fd[INS_MAX_INSTANCES];
|
||||||
static int gyro_fd[INS_MAX_INSTANCES];
|
static int gyro_fd[INS_MAX_INSTANCES];
|
||||||
|
@ -210,7 +210,7 @@ void loop(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
#else
|
#else
|
||||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
void setup() {}
|
void setup() {}
|
||||||
void loop() {}
|
void loop() {}
|
||||||
#endif // CONFIG_HAL_BOARD
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
#define SHOW_POLES_BREAKDOWN 0
|
#define SHOW_POLES_BREAKDOWN 0
|
||||||
|
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
static const struct {
|
static const struct {
|
||||||
Vector2f wp1, wp2, location;
|
Vector2f wp1, wp2, location;
|
||||||
|
|
|
@ -12,7 +12,7 @@
|
||||||
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
||||||
#include <AP_HAL_Linux/AP_HAL_Linux.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
|
* this is the boundary of the 2010 outback challenge
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
#include <AP_RangeFinder/AP_RangeFinder.h>
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
||||||
#include <AP_OpticalFlow/AP_OpticalFlow.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)
|
static void print_vector(Vector3f &v)
|
||||||
{
|
{
|
||||||
|
|
|
@ -38,7 +38,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
class MissionTest {
|
class MissionTest {
|
||||||
public:
|
public:
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
RC_Channel rc1(0), rc2(1), rc3(2), rc4(3);
|
RC_Channel rc1(0), rc2(1), rc3(2), rc4(3);
|
||||||
|
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
RC_Channel rc1(0), rc2(1), rc3(2), rc4(3);
|
RC_Channel rc1(0), rc2(1), rc3(2), rc4(3);
|
||||||
|
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
#include <AP_Mount/AP_Mount.h>
|
#include <AP_Mount/AP_Mount.h>
|
||||||
|
|
||||||
#include <AP_HAL_AVR/AP_HAL_AVR.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 () {
|
void setup () {
|
||||||
hal.console->println_P(PSTR("Unit test for AP_Mount. This sketch"
|
hal.console->println_P(PSTR("Unit test for AP_Mount. This sketch"
|
||||||
|
|
|
@ -18,7 +18,7 @@
|
||||||
#include <StorageManager/StorageManager.h>
|
#include <StorageManager/StorageManager.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
// create board led object
|
// create board led object
|
||||||
AP_BoardLED board_led;
|
AP_BoardLED board_led;
|
||||||
|
|
|
@ -34,7 +34,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.h>
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
static ToshibaLED_PX4 toshiba_led;
|
static ToshibaLED_PX4 toshiba_led;
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.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;
|
static OpticalFlow optflow;
|
||||||
|
|
||||||
|
|
|
@ -15,7 +15,7 @@
|
||||||
#include <AP_Notify/AP_Notify.h>
|
#include <AP_Notify/AP_Notify.h>
|
||||||
#include <StorageManager/StorageManager.h>
|
#include <StorageManager/StorageManager.h>
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
// Relay
|
// Relay
|
||||||
AP_Relay relay;
|
AP_Relay relay;
|
||||||
|
|
|
@ -12,7 +12,7 @@
|
||||||
#include <StorageManager/StorageManager.h>
|
#include <StorageManager/StorageManager.h>
|
||||||
#include <AP_PerfMon/AP_PerfMon.h> // PerfMonitor library
|
#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(setup)
|
||||||
AP_PERFMON_REGISTER_FN(loop)
|
AP_PERFMON_REGISTER_FN(loop)
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
#include <AP_Rally/AP_Rally.h>
|
#include <AP_Rally/AP_Rally.h>
|
||||||
#include <AP_SerialManager/AP_SerialManager.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 AP_SerialManager serial_manager;
|
||||||
static RangeFinder sonar {serial_manager};
|
static RangeFinder sonar {serial_manager};
|
||||||
|
|
|
@ -40,7 +40,7 @@
|
||||||
#include <AP_HAL_Empty/AP_HAL_Empty.h>
|
#include <AP_HAL_Empty/AP_HAL_Empty.h>
|
||||||
#include <AP_HAL_PX4/AP_HAL_PX4.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 {
|
class SchedTest {
|
||||||
public:
|
public:
|
||||||
|
|
|
@ -39,7 +39,7 @@
|
||||||
#include <AP_BattMonitor/AP_BattMonitor.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();
|
||||||
|
|
||||||
#define LOG_TEST_MSG 1
|
#define LOG_TEST_MSG 1
|
||||||
|
|
||||||
|
|
|
@ -13,7 +13,7 @@
|
||||||
#include <Filter/Filter.h>
|
#include <Filter/Filter.h>
|
||||||
#include <Filter/DerivativeFilter.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;
|
DerivativeFilter<float,11> derivative;
|
||||||
|
|
||||||
|
|
|
@ -16,7 +16,7 @@
|
||||||
#include <Filter/ModeFilter.h> // ModeFilter class (inherits from Filter class)
|
#include <Filter/ModeFilter.h> // ModeFilter class (inherits from Filter class)
|
||||||
#include <Filter/AverageFilter.h> // AverageFilter 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};
|
int16_t rangevalue[] = {31000, 31000, 50, 55, 60, 55, 10, 0, 31000};
|
||||||
|
|
||||||
|
|
|
@ -13,7 +13,7 @@
|
||||||
#include <Filter/Filter.h> // Filter library
|
#include <Filter/Filter.h> // Filter library
|
||||||
#include <Filter/LowPassFilter.h> // LowPassFilter class (inherits from Filter class)
|
#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
|
// create a global instance of the class
|
||||||
LowPassFilterFloat low_pass_filter;
|
LowPassFilterFloat low_pass_filter;
|
||||||
|
|
|
@ -15,7 +15,7 @@
|
||||||
#include <Filter/Filter.h> // Filter library
|
#include <Filter/Filter.h> // Filter library
|
||||||
#include <Filter/LowPassFilter2p.h>
|
#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
|
// craete an instance with 800Hz sample rate and 30Hz cutoff
|
||||||
static LowPassFilter2pFloat low_pass_filter(800, 30);
|
static LowPassFilter2pFloat low_pass_filter(800, 30);
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#include "simplegcs.h"
|
#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() {
|
void flush_console_to_statustext() {
|
||||||
uint8_t data[50];
|
uint8_t data[50];
|
||||||
|
|
|
@ -43,7 +43,7 @@
|
||||||
#include <SITL/SITL.h>
|
#include <SITL/SITL.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
|
static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
|
||||||
static GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS];
|
static GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS];
|
||||||
|
|
|
@ -15,7 +15,7 @@
|
||||||
#include <AP_HAL_SITL/AP_HAL_SITL.h>
|
#include <AP_HAL_SITL/AP_HAL_SITL.h>
|
||||||
#include <AP_HAL_Empty/AP_HAL_Empty.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_in;
|
||||||
long radio_trim;
|
long radio_trim;
|
||||||
|
|
|
@ -46,7 +46,7 @@
|
||||||
#include <AP_HAL/UARTDriver.h>
|
#include <AP_HAL/UARTDriver.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
#define NUM_CHANNELS 8
|
#define NUM_CHANNELS 8
|
||||||
|
|
||||||
|
|
|
@ -40,7 +40,7 @@
|
||||||
#include <AP_Scheduler/AP_Scheduler.h>
|
#include <AP_Scheduler/AP_Scheduler.h>
|
||||||
#include <AP_RangeFinder/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::get_HAL();
|
||||||
|
|
||||||
#define DO_INITIALISATION 1
|
#define DO_INITIALISATION 1
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue