AP_InertialSensor: update for new notify API

This commit is contained in:
Andrew Tridgell 2013-08-29 13:13:28 +10:00
parent 495c4bbbbe
commit 65a490c209
2 changed files with 1 additions and 9 deletions

View File

@ -5,6 +5,7 @@
#include <AP_Common.h>
#include <AP_HAL.h>
#include <AP_Notify.h>
extern const AP_HAL::HAL& hal;
@ -159,9 +160,6 @@ AP_InertialSensor::_init_gyro(void (*flash_leds_cb)(bool on))
update();
ins_gyro = get_gyro();
// give leds a chance to update
AP_Notify::update();
}
// the strategy is to average 200 points over 1 second, then do it
@ -185,8 +183,6 @@ AP_InertialSensor::_init_gyro(void (*flash_leds_cb)(bool on))
ins_gyro = get_gyro();
gyro_sum += ins_gyro;
hal.scheduler->delay(5);
// give leds a chance to update
AP_Notify::update();
}
gyro_avg = gyro_sum / i;
@ -285,9 +281,6 @@ AP_InertialSensor::_init_accel(void (*flash_leds_cb)(bool on))
flashcount = 0;
}
flashcount++;
// give leds a chance to update
AP_Notify::update();
}
// null gravity from the Z accel

View File

@ -10,7 +10,6 @@
#include <stdint.h>
#include <AP_HAL.h>
#include <AP_Math.h>
#include <AP_Notify.h>
#include "AP_InertialSensor_UserInteract.h"
/* AP_InertialSensor is an abstraction for gyro and accel measurements
* which are correctly aligned to the body axes and scaled to SI units.