mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_Airspeed: remove checks for HAL_BOARD_APM2 and HAL_BOARD_APM1
This commit is contained in:
parent
124937ab61
commit
221d822573
@ -26,12 +26,7 @@
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
||||
#define ARSPD_DEFAULT_PIN 64
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||
#define ARSPD_DEFAULT_PIN 0
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#define ARSPD_DEFAULT_PIN 1
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
#include <sys/stat.h>
|
||||
|
@ -30,18 +30,8 @@ extern const AP_HAL::HAL& hal;
|
||||
// scaling for 3DR analog airspeed sensor
|
||||
#define VOLTS_TO_PASCAL 819
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
extern AP_ADC_ADS7844 apm1_adc;
|
||||
#endif
|
||||
|
||||
bool AP_Airspeed_Analog::init()
|
||||
{
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
if (_pin == 64) {
|
||||
_source = new AP_ADC_AnalogSource( &apm1_adc, 7, 1.0f);
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
_source = hal.analogin->channel(_pin);
|
||||
return true;
|
||||
}
|
||||
|
@ -37,8 +37,6 @@ void Airspeed_Calibration::init(float initial_ratio)
|
||||
/*
|
||||
update the state of the airspeed calibration - needs to be called
|
||||
once a second
|
||||
|
||||
On an AVR2560 this costs 1.9 milliseconds per call
|
||||
*/
|
||||
float Airspeed_Calibration::update(float airspeed, const Vector3f &vg)
|
||||
{
|
||||
|
@ -24,10 +24,6 @@
|
||||
#include <AP_ADC_AnalogSource/AP_ADC_AnalogSource.h>
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
AP_ADC_ADS7844 apm1_adc;
|
||||
#endif
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
static AP_Vehicle::FixedWing aparm;
|
||||
|
Loading…
Reference in New Issue
Block a user