mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: make a static-const hal references references to external symbol
This commit is contained in:
parent
2d2fdf8bd0
commit
c917cd4dbb
|
@ -7,7 +7,7 @@
|
||||||
|
|
||||||
#include "AnalogIn_Navio2.h"
|
#include "AnalogIn_Navio2.h"
|
||||||
|
|
||||||
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#define ADC_BASE_PATH "/sys/kernel/rcio/adc"
|
#define ADC_BASE_PATH "/sys/kernel/rcio/adc"
|
||||||
|
|
||||||
|
|
|
@ -4,7 +4,7 @@
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
|
||||||
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
DigitalSource::DigitalSource(uint8_t v) :
|
DigitalSource::DigitalSource(uint8_t v) :
|
||||||
_v(v)
|
_v(v)
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
|
||||||
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
GPIO_RPI::GPIO_RPI()
|
GPIO_RPI::GPIO_RPI()
|
||||||
{
|
{
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
|
||||||
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#define UINT32_MAX_STR "4294967295"
|
#define UINT32_MAX_STR "4294967295"
|
||||||
|
|
||||||
|
|
|
@ -409,14 +409,14 @@ void HAL_Linux::setup_signal_handlers() const
|
||||||
sigaction(SIGINT, &sa, NULL);
|
sigaction(SIGINT, &sa, NULL);
|
||||||
}
|
}
|
||||||
|
|
||||||
static HAL_Linux halInstance;
|
HAL_Linux hal_linux;
|
||||||
|
|
||||||
void HAL_Linux::exit_signal_handler(int signum)
|
void HAL_Linux::exit_signal_handler(int signum)
|
||||||
{
|
{
|
||||||
halInstance._should_exit = true;
|
hal_linux._should_exit = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
const AP_HAL::HAL &AP_HAL::get_HAL()
|
const AP_HAL::HAL &AP_HAL::get_HAL()
|
||||||
{
|
{
|
||||||
return halInstance;
|
return hal_linux;
|
||||||
}
|
}
|
||||||
|
|
|
@ -56,9 +56,9 @@
|
||||||
#define I2C_RDRW_IOCTL_MAX_MSGS 42
|
#define I2C_RDRW_IOCTL_MAX_MSGS 42
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
namespace Linux {
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
namespace Linux {
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* TODO: move to Util or other upper class to be used by others
|
* TODO: move to Util or other upper class to be used by others
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
namespace Linux {
|
namespace Linux {
|
||||||
|
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
namespace Linux {
|
namespace Linux {
|
||||||
|
|
||||||
|
|
|
@ -33,7 +33,7 @@
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
|
||||||
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
Perf *Perf::_singleton;
|
Perf *Perf::_singleton;
|
||||||
|
|
||||||
|
|
|
@ -91,7 +91,7 @@ using namespace Linux;
|
||||||
* uint16_t duty = 1823;
|
* uint16_t duty = 1823;
|
||||||
*/
|
*/
|
||||||
|
|
||||||
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
RCOutput_AeroIO::RCOutput_AeroIO()
|
RCOutput_AeroIO::RCOutput_AeroIO()
|
||||||
: _freq_buffer(new uint16_t[PWM_CHAN_COUNT])
|
: _freq_buffer(new uint16_t[PWM_CHAN_COUNT])
|
||||||
|
|
|
@ -81,7 +81,7 @@ enum BLDC_STATUS {
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
|
||||||
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
RCOutput_Bebop::RCOutput_Bebop(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
RCOutput_Bebop::RCOutput_Bebop(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||||
: _dev(std::move(dev))
|
: _dev(std::move(dev))
|
||||||
|
|
|
@ -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::get_HAL();
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
RCOutput_PCA9685::RCOutput_PCA9685(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
RCOutput_PCA9685::RCOutput_PCA9685(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
bool external_clock,
|
bool external_clock,
|
||||||
|
|
|
@ -39,9 +39,9 @@
|
||||||
|
|
||||||
#define DEBUG 0
|
#define DEBUG 0
|
||||||
|
|
||||||
namespace Linux {
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
namespace Linux {
|
||||||
|
|
||||||
#define MHZ (1000U*1000U)
|
#define MHZ (1000U*1000U)
|
||||||
#define KHZ (1000U)
|
#define KHZ (1000U)
|
||||||
|
|
|
@ -20,7 +20,7 @@
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <SRV_Channel/SRV_Channel.h>
|
#include <SRV_Channel/SRV_Channel.h>
|
||||||
|
|
||||||
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#define LED_OFF 0
|
#define LED_OFF 0
|
||||||
#define LED_FULL_BRIGHT 255
|
#define LED_FULL_BRIGHT 255
|
||||||
|
|
Loading…
Reference in New Issue