Plane: update for new AP_InertialSensor API
This commit is contained in:
parent
dbcd02f2be
commit
240e87dc2c
@ -219,29 +219,11 @@ static AP_Compass_HIL compass;
|
||||
#error Unrecognized CONFIG_COMPASS setting
|
||||
#endif
|
||||
|
||||
#if CONFIG_INS_TYPE == HAL_INS_OILPAN || CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
AP_ADC_ADS7844 apm1_adc;
|
||||
#endif
|
||||
|
||||
#if CONFIG_INS_TYPE == HAL_INS_MPU6000
|
||||
AP_InertialSensor_MPU6000 ins;
|
||||
#elif CONFIG_INS_TYPE == HAL_INS_PX4
|
||||
AP_InertialSensor_PX4 ins;
|
||||
#elif CONFIG_INS_TYPE == HAL_INS_VRBRAIN
|
||||
AP_InertialSensor_VRBRAIN ins;
|
||||
#elif CONFIG_INS_TYPE == HAL_INS_HIL
|
||||
AP_InertialSensor_HIL ins;
|
||||
#elif CONFIG_INS_TYPE == HAL_INS_OILPAN
|
||||
AP_InertialSensor_Oilpan ins( &apm1_adc );
|
||||
#elif CONFIG_INS_TYPE == HAL_INS_FLYMAPLE
|
||||
AP_InertialSensor_Flymaple ins;
|
||||
#elif CONFIG_INS_TYPE == HAL_INS_L3G4200D
|
||||
AP_InertialSensor_L3G4200D ins;
|
||||
#elif CONFIG_INS_TYPE == HAL_INS_MPU9250
|
||||
AP_InertialSensor_MPU9250 ins;
|
||||
#else
|
||||
#error Unrecognised CONFIG_INS_TYPE setting.
|
||||
#endif // CONFIG_INS_TYPE
|
||||
AP_InertialSensor ins;
|
||||
|
||||
// Inertial Navigation EKF
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
@ -844,9 +826,8 @@ void setup() {
|
||||
void loop()
|
||||
{
|
||||
// wait for an INS sample
|
||||
if (!ins.wait_for_sample(1000)) {
|
||||
return;
|
||||
}
|
||||
ins.wait_for_sample();
|
||||
|
||||
uint32_t timer = hal.scheduler->micros();
|
||||
|
||||
delta_us_fast_loop = timer - fast_loopTimer_us;
|
||||
|
@ -85,7 +85,6 @@
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// sensor types
|
||||
|
||||
#define CONFIG_INS_TYPE HAL_INS_DEFAULT
|
||||
#define CONFIG_BARO HAL_BARO_DEFAULT
|
||||
#define CONFIG_COMPASS HAL_COMPASS_DEFAULT
|
||||
|
||||
@ -103,8 +102,6 @@
|
||||
#if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode
|
||||
#undef CONFIG_BARO
|
||||
#define CONFIG_BARO HAL_BARO_HIL
|
||||
#undef CONFIG_INS_TYPE
|
||||
#define CONFIG_INS_TYPE HAL_INS_HIL
|
||||
#undef CONFIG_COMPASS
|
||||
#define CONFIG_COMPASS HAL_COMPASS_HIL
|
||||
#endif
|
||||
|
@ -150,7 +150,7 @@ static void init_ardupilot()
|
||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||
hal.scheduler->register_delay_callback(mavlink_delay_cb, 5);
|
||||
|
||||
#if CONFIG_INS_TYPE == CONFIG_INS_OILPAN || CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
apm1_adc.Init(); // APM ADC library initialization
|
||||
#endif
|
||||
|
||||
@ -499,6 +499,9 @@ static void startup_INS_ground(bool do_accel_init)
|
||||
gcs_send_text_P(SEVERITY_LOW, PSTR("Waiting for first HIL_STATE message"));
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
// set INS to HIL mode
|
||||
ins.set_hil_mode();
|
||||
#endif
|
||||
|
||||
AP_InertialSensor::Start_style style;
|
||||
|
@ -360,7 +360,7 @@ test_shell(uint8_t argc, const Menu::arg *argv)
|
||||
//-------------------------------------------------------------------------------------------
|
||||
// tests in this section are for real sensors or sensors that have been simulated
|
||||
|
||||
#if CONFIG_INS_TYPE == CONFIG_INS_OILPAN || CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||
static int8_t
|
||||
test_adc(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
@ -379,7 +379,7 @@ test_adc(uint8_t argc, const Menu::arg *argv)
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // CONFIG_INS_TYPE
|
||||
#endif
|
||||
|
||||
static int8_t
|
||||
test_gps(uint8_t argc, const Menu::arg *argv)
|
||||
|
Loading…
Reference in New Issue
Block a user