mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Plane: enable Oilpan and BMP085 on Linux
This commit is contained in:
parent
30b6b23b10
commit
444d053dc2
@ -181,10 +181,6 @@ static GPS *g_gps;
|
|||||||
// flight modes convenience array
|
// flight modes convenience array
|
||||||
static AP_Int8 *flight_modes = &g.flight_mode1;
|
static AP_Int8 *flight_modes = &g.flight_mode1;
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
||||||
AP_ADC_ADS7844 apm1_adc;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if CONFIG_BARO == AP_BARO_BMP085
|
#if CONFIG_BARO == AP_BARO_BMP085
|
||||||
static AP_Baro_BMP085 barometer;
|
static AP_Baro_BMP085 barometer;
|
||||||
#elif CONFIG_BARO == AP_BARO_PX4
|
#elif CONFIG_BARO == AP_BARO_PX4
|
||||||
@ -242,6 +238,10 @@ AP_GPS_HIL g_gps_driver;
|
|||||||
#error Unrecognised GPS_PROTOCOL setting.
|
#error Unrecognised GPS_PROTOCOL setting.
|
||||||
#endif // GPS PROTOCOL
|
#endif // GPS PROTOCOL
|
||||||
|
|
||||||
|
#if CONFIG_INS_TYPE == CONFIG_INS_OILPAN || CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
|
AP_ADC_ADS7844 apm1_adc;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if CONFIG_INS_TYPE == CONFIG_INS_MPU6000
|
#if CONFIG_INS_TYPE == CONFIG_INS_MPU6000
|
||||||
AP_InertialSensor_MPU6000 ins;
|
AP_InertialSensor_MPU6000 ins;
|
||||||
#elif CONFIG_INS_TYPE == CONFIG_INS_PX4
|
#elif CONFIG_INS_TYPE == CONFIG_INS_PX4
|
||||||
|
@ -134,9 +134,9 @@
|
|||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
# define BATTERY_VOLT_PIN -1
|
# define BATTERY_VOLT_PIN -1
|
||||||
# define BATTERY_CURR_PIN -1
|
# define BATTERY_CURR_PIN -1
|
||||||
# define CONFIG_INS_TYPE CONFIG_INS_HIL
|
# define CONFIG_INS_TYPE CONFIG_INS_OILPAN
|
||||||
# define CONFIG_BARO AP_BARO_HIL
|
# define CONFIG_BARO AP_BARO_BMP085
|
||||||
# define CONFIG_COMPASS AP_COMPASS_HIL
|
# define CONFIG_COMPASS AP_COMPASS_HMC5843
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
@ -137,9 +137,9 @@ static void init_ardupilot()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
#if CONFIG_INS_TYPE == CONFIG_INS_OILPAN || CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
apm1_adc.Init(); // APM ADC library initialization
|
apm1_adc.Init(); // APM ADC library initialization
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// initialise airspeed sensor
|
// initialise airspeed sensor
|
||||||
airspeed.init();
|
airspeed.init();
|
||||||
|
@ -413,7 +413,7 @@ test_shell(uint8_t argc, const Menu::arg *argv)
|
|||||||
//-------------------------------------------------------------------------------------------
|
//-------------------------------------------------------------------------------------------
|
||||||
// tests in this section are for real sensors or sensors that have been simulated
|
// tests in this section are for real sensors or sensors that have been simulated
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
#if CONFIG_INS_TYPE == CONFIG_INS_OILPAN || CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
static int8_t
|
static int8_t
|
||||||
test_adc(uint8_t argc, const Menu::arg *argv)
|
test_adc(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
@ -432,7 +432,7 @@ test_adc(uint8_t argc, const Menu::arg *argv)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
#endif // CONFIG_INS_TYPE
|
||||||
|
|
||||||
static int8_t
|
static int8_t
|
||||||
test_gps(uint8_t argc, const Menu::arg *argv)
|
test_gps(uint8_t argc, const Menu::arg *argv)
|
||||||
|
Loading…
Reference in New Issue
Block a user