Browse Source

Rover: convert to new AP_InertialSensor API

master
Andrew Tridgell 10 years ago
parent
commit
35b558cfc2
  1. 27
      APMrover2/APMrover2.pde
  2. 3
      APMrover2/config.h
  3. 4
      APMrover2/test.pde

27
APMrover2/APMrover2.pde

@ -228,29 +228,11 @@ static AP_Compass_HIL compass;
#error Unrecognized CONFIG_COMPASS setting #error Unrecognized CONFIG_COMPASS setting
#endif #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; AP_ADC_ADS7844 apm1_adc;
#endif #endif
#if CONFIG_INS_TYPE == HAL_INS_MPU6000 AP_InertialSensor ins;
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
// Inertial Navigation EKF // Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE #if AP_AHRS_NAVEKF_AVAILABLE
@ -586,9 +568,8 @@ void setup() {
void loop() void loop()
{ {
// wait for an INS sample // wait for an INS sample
if (!ins.wait_for_sample(1000)) { ins.wait_for_sample();
return;
}
uint32_t timer = hal.scheduler->micros(); uint32_t timer = hal.scheduler->micros();
delta_us_fast_loop = timer - fast_loopTimer_us; delta_us_fast_loop = timer - fast_loopTimer_us;

3
APMrover2/config.h

@ -51,7 +51,6 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// sensor types // sensor types
#define CONFIG_INS_TYPE HAL_INS_DEFAULT
#define CONFIG_BARO HAL_BARO_DEFAULT #define CONFIG_BARO HAL_BARO_DEFAULT
#define CONFIG_COMPASS HAL_COMPASS_DEFAULT #define CONFIG_COMPASS HAL_COMPASS_DEFAULT
@ -69,8 +68,6 @@
#if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode #if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode
#undef CONFIG_BARO #undef CONFIG_BARO
#define CONFIG_BARO HAL_BARO_HIL #define CONFIG_BARO HAL_BARO_HIL
#undef CONFIG_INS_TYPE
#define CONFIG_INS_TYPE HAL_INS_HIL
#undef CONFIG_COMPASS #undef CONFIG_COMPASS
#define CONFIG_COMPASS HAL_COMPASS_HIL #define CONFIG_COMPASS HAL_COMPASS_HIL
#endif #endif

4
APMrover2/test.pde

@ -349,7 +349,7 @@ test_ins(uint8_t argc, const Menu::arg *argv)
uint8_t medium_loopCounter = 0; uint8_t medium_loopCounter = 0;
while(1){ while(1){
ins.wait_for_sample(1000); ins.wait_for_sample();
ahrs.update(); ahrs.update();
@ -409,7 +409,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
uint8_t medium_loopCounter = 0; uint8_t medium_loopCounter = 0;
while(1) { while(1) {
ins.wait_for_sample(1000); ins.wait_for_sample();
ahrs.update(); ahrs.update();
medium_loopCounter++; medium_loopCounter++;

Loading…
Cancel
Save