mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_InertialSensor: remove sei in data interrupt handler
This commit is contained in:
parent
af852aa6a9
commit
1019fb45e7
@ -364,11 +364,8 @@ void AP_InertialSensor_MPU6000::data_interrupt(void)
|
|||||||
{
|
{
|
||||||
// record time that data was available
|
// record time that data was available
|
||||||
_last_sample_time_micros = hal.scheduler->micros();
|
_last_sample_time_micros = hal.scheduler->micros();
|
||||||
|
// queue our read process to run after any currently running timed
|
||||||
// re-enable interrupts
|
// processes complete
|
||||||
sei();
|
|
||||||
|
|
||||||
// queue our read process to run after any currently running timed processes complete
|
|
||||||
hal.scheduler->defer_timer_process( AP_InertialSensor_MPU6000::read );
|
hal.scheduler->defer_timer_process( AP_InertialSensor_MPU6000::read );
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user