mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_InertialSensor: fixed semaphore error on startup for MPU6000
This commit is contained in:
parent
3262022195
commit
80def01fbe
@ -217,7 +217,10 @@ uint16_t AP_InertialSensor_MPU6000::_init_sensor( Sample_rate sample_rate )
|
|||||||
* its caller. */
|
* its caller. */
|
||||||
_last_sample_time_micros = hal.scheduler->micros();
|
_last_sample_time_micros = hal.scheduler->micros();
|
||||||
hal.scheduler->delay(10);
|
hal.scheduler->delay(10);
|
||||||
|
if (_spi_sem->take(100)) {
|
||||||
_read_data_transaction();
|
_read_data_transaction();
|
||||||
|
_spi_sem->give();
|
||||||
|
}
|
||||||
|
|
||||||
// start the timer process to read samples
|
// start the timer process to read samples
|
||||||
hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_MPU6000::_poll_data));
|
hal.scheduler->register_timer_process(AP_HAL_MEMBERPROC(&AP_InertialSensor_MPU6000::_poll_data));
|
||||||
|
Loading…
Reference in New Issue
Block a user