mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: use Empty version if not implemented
There's little point in having the Linux::AnalogIn just to implement and empty interface. All implementations inside AP_HAL_Linux are already inheriting directly from AP_HAL, so just remove it.
This commit is contained in:
parent
47d2f8dc6d
commit
9acffc8868
|
@ -9,8 +9,6 @@ namespace Linux {
|
||||||
class I2CDriver;
|
class I2CDriver;
|
||||||
class SPIDeviceManager;
|
class SPIDeviceManager;
|
||||||
class SPIDeviceDriver;
|
class SPIDeviceDriver;
|
||||||
class AnalogSource;
|
|
||||||
class AnalogIn;
|
|
||||||
class Storage;
|
class Storage;
|
||||||
class GPIO_BBB;
|
class GPIO_BBB;
|
||||||
class GPIO_RPI;
|
class GPIO_RPI;
|
||||||
|
|
|
@ -10,7 +10,6 @@
|
||||||
#include "I2CDevice.h"
|
#include "I2CDevice.h"
|
||||||
#include "I2CDriver.h"
|
#include "I2CDriver.h"
|
||||||
#include "SPIDriver.h"
|
#include "SPIDriver.h"
|
||||||
#include "AnalogIn.h"
|
|
||||||
#include "AnalogIn_ADS1115.h"
|
#include "AnalogIn_ADS1115.h"
|
||||||
#include "AnalogIn_IIO.h"
|
#include "AnalogIn_IIO.h"
|
||||||
#include "AnalogIn_Raspilot.h"
|
#include "AnalogIn_Raspilot.h"
|
||||||
|
|
|
@ -1,42 +0,0 @@
|
||||||
#include "AnalogIn.h"
|
|
||||||
|
|
||||||
using namespace Linux;
|
|
||||||
|
|
||||||
AnalogSource::AnalogSource(float v) :
|
|
||||||
_v(v)
|
|
||||||
{}
|
|
||||||
|
|
||||||
float AnalogSource::read_average() {
|
|
||||||
return _v;
|
|
||||||
}
|
|
||||||
|
|
||||||
float AnalogSource::voltage_average() {
|
|
||||||
return 5.0 * _v / 1024.0;
|
|
||||||
}
|
|
||||||
|
|
||||||
float AnalogSource::voltage_latest() {
|
|
||||||
return 5.0 * _v / 1024.0;
|
|
||||||
}
|
|
||||||
|
|
||||||
float AnalogSource::read_latest() {
|
|
||||||
return _v;
|
|
||||||
}
|
|
||||||
|
|
||||||
void AnalogSource::set_pin(uint8_t p)
|
|
||||||
{}
|
|
||||||
|
|
||||||
void AnalogSource::set_stop_pin(uint8_t p)
|
|
||||||
{}
|
|
||||||
|
|
||||||
void AnalogSource::set_settle_time(uint16_t settle_time_ms)
|
|
||||||
{}
|
|
||||||
|
|
||||||
AnalogIn::AnalogIn()
|
|
||||||
{}
|
|
||||||
|
|
||||||
void AnalogIn::init()
|
|
||||||
{}
|
|
||||||
|
|
||||||
AP_HAL::AnalogSource* AnalogIn::channel(int16_t n) {
|
|
||||||
return new AnalogSource(1.11);
|
|
||||||
}
|
|
|
@ -1,29 +0,0 @@
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#include "AP_HAL_Linux.h"
|
|
||||||
|
|
||||||
class Linux::AnalogSource : public AP_HAL::AnalogSource {
|
|
||||||
public:
|
|
||||||
AnalogSource(float v);
|
|
||||||
float read_average();
|
|
||||||
float read_latest();
|
|
||||||
void set_pin(uint8_t p);
|
|
||||||
void set_stop_pin(uint8_t p);
|
|
||||||
void set_settle_time(uint16_t settle_time_ms);
|
|
||||||
float voltage_average();
|
|
||||||
float voltage_latest();
|
|
||||||
float voltage_average_ratiometric() { return voltage_average(); }
|
|
||||||
private:
|
|
||||||
float _v;
|
|
||||||
};
|
|
||||||
|
|
||||||
class Linux::AnalogIn : public AP_HAL::AnalogIn {
|
|
||||||
public:
|
|
||||||
AnalogIn();
|
|
||||||
void init();
|
|
||||||
AP_HAL::AnalogSource* channel(int16_t n);
|
|
||||||
|
|
||||||
// we don't yet know how to get the board voltage
|
|
||||||
float board_voltage(void) { return 0.0f; }
|
|
||||||
|
|
||||||
};
|
|
|
@ -76,8 +76,6 @@ static SPIDeviceManager spiDeviceManager;
|
||||||
static AnalogIn_ADS1115 analogIn;
|
static AnalogIn_ADS1115 analogIn;
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
||||||
static AnalogIn_Raspilot analogIn;
|
static AnalogIn_Raspilot analogIn;
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
|
|
||||||
static Empty::AnalogIn analogIn;
|
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \
|
||||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD || \
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD || \
|
||||||
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI || \
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI || \
|
||||||
|
@ -86,7 +84,7 @@ static AnalogIn_IIO analogIn;
|
||||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
|
||||||
static AnalogIn_Navio2 analogIn;
|
static AnalogIn_Navio2 analogIn;
|
||||||
#else
|
#else
|
||||||
static AnalogIn analogIn;
|
static Empty::AnalogIn analogIn;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -17,7 +17,6 @@
|
||||||
#include <dspal_types.h>
|
#include <dspal_types.h>
|
||||||
|
|
||||||
#include "UARTDriver.h"
|
#include "UARTDriver.h"
|
||||||
//#include "AnalogIn.h"
|
|
||||||
#include "Storage.h"
|
#include "Storage.h"
|
||||||
#include "RCOutput.h"
|
#include "RCOutput.h"
|
||||||
#include <AP_Scheduler/AP_Scheduler.h>
|
#include <AP_Scheduler/AP_Scheduler.h>
|
||||||
|
@ -178,9 +177,6 @@ void Scheduler::_run_timers(bool called_from_timer_thread)
|
||||||
_failsafe();
|
_failsafe();
|
||||||
}
|
}
|
||||||
|
|
||||||
// process analog input
|
|
||||||
// ((QURTAnalogIn *)hal.analogin)->_timer_tick();
|
|
||||||
|
|
||||||
_in_timer_proc = false;
|
_in_timer_proc = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue