AP_InertialSensor: use AP_TimerProcess's queue_process to run read from MPU6000 after any currently running processes complete
This commit is contained in:
parent
55ef1e0a29
commit
7a265dbf61
@ -353,7 +353,7 @@ static int16_t spi_transfer_16(void)
|
|||||||
* to ensure this is the case, these other devices must perform their SPI reads after being
|
* to ensure this is the case, these other devices must perform their SPI reads after being
|
||||||
* called by the AP_TimerProcess.
|
* called by the AP_TimerProcess.
|
||||||
*/
|
*/
|
||||||
void AP_InertialSensor_MPU6000::read()
|
void AP_InertialSensor_MPU6000::read(uint32_t)
|
||||||
{
|
{
|
||||||
// record time that data was available
|
// record time that data was available
|
||||||
_last_sample_time_micros = micros();
|
_last_sample_time_micros = micros();
|
||||||
@ -407,17 +407,11 @@ void AP_InertialSensor_MPU6000::register_write(uint8_t reg, uint8_t val)
|
|||||||
// MPU6000 new data interrupt on INT6
|
// MPU6000 new data interrupt on INT6
|
||||||
void AP_InertialSensor_MPU6000::data_interrupt(void)
|
void AP_InertialSensor_MPU6000::data_interrupt(void)
|
||||||
{
|
{
|
||||||
// stop the timer firing, to prevent SPI bus accesses by other drivers
|
|
||||||
_scheduler->suspend_timer();
|
|
||||||
|
|
||||||
// re-enable interrupts
|
// re-enable interrupts
|
||||||
sei();
|
sei();
|
||||||
|
|
||||||
// read in samples from the MPU6000's data registers
|
// queue our read process to run after any currently running timed processes complete
|
||||||
read();
|
_scheduler->queue_process( AP_InertialSensor_MPU6000::read );
|
||||||
|
|
||||||
// resume the timer
|
|
||||||
_scheduler->resume_timer();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_InertialSensor_MPU6000::hardware_init()
|
void AP_InertialSensor_MPU6000::hardware_init()
|
||||||
|
@ -57,7 +57,7 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
static void read();
|
static void read(uint32_t);
|
||||||
static void data_interrupt(void);
|
static void data_interrupt(void);
|
||||||
static uint8_t register_read( uint8_t reg );
|
static uint8_t register_read( uint8_t reg );
|
||||||
static void register_write( uint8_t reg, uint8_t val );
|
static void register_write( uint8_t reg, uint8_t val );
|
||||||
|
Loading…
Reference in New Issue
Block a user