mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 11:08:29 -04:00
AP_InertialSensor: Minor correction to comments in AP_InertialSensor_Flymaple.cpp
This commit is contained in:
parent
0920d9ac49
commit
fe6cacf081
@ -254,7 +254,7 @@ void AP_InertialSensor_Flymaple::_accumulate(void)
|
||||
// ADXL345 is in the default FIFO bypass mode, so the FIFO is not used
|
||||
uint8_t buffer[6];
|
||||
uint64_t now = hal.scheduler->micros();
|
||||
// This takes about 500us at 200kHz I2C speed
|
||||
// This takes about 250us at 400kHz I2C speed
|
||||
if ((now - _last_accel_timestamp) >= raw_sample_interval_us
|
||||
&& hal.i2c->readRegisters(FLYMAPLE_ACCELEROMETER_ADDRESS, FLYMAPLE_ACCELEROMETER_ADXLREG_DATAX0, 6, buffer) == 0)
|
||||
{
|
||||
@ -274,7 +274,7 @@ void AP_InertialSensor_Flymaple::_accumulate(void)
|
||||
|
||||
// Read gyro
|
||||
now = hal.scheduler->micros();
|
||||
// This takes about 500us at 200kHz I2C speed
|
||||
// This takes about 250us at 400kHz I2C speed
|
||||
if ((now - _last_gyro_timestamp) >= raw_sample_interval_us
|
||||
&& hal.i2c->readRegisters(FLYMAPLE_GYRO_ADDRESS, FLYMAPLE_GYRO_GYROX_H, 6, buffer) == 0)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user