mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-11 09:32:57 +08:00
MPU6K: Use usleep where usleep should be used instead of up_udelay()
This commit is contained in:
@@ -544,7 +544,7 @@ void MPU6000::reset()
|
||||
write_reg(MPUREG_USER_CTRL, BIT_I2C_IF_DIS);
|
||||
irqrestore(state);
|
||||
|
||||
up_udelay(1000);
|
||||
usleep(1000);
|
||||
|
||||
// SAMPLE RATE
|
||||
_set_sample_rate(_sample_rate);
|
||||
|
||||
Reference in New Issue
Block a user