AP_InertialSensor: fixed from review by Lucas

This commit is contained in:
Andrew Tridgell 2016-11-09 12:16:54 +11:00
parent 81b933d9d0
commit 2f01dfe81c
2 changed files with 2 additions and 4 deletions

View File

@ -568,8 +568,6 @@ void AP_InertialSensor_MPU6000::_read_fifo()
uint16_t bytes_read;
uint8_t *rx = _fifo_buffer;
//static_assert(MAX_DATA_READ <= 100, "Too big to keep on stack");
if (!_block_read(MPUREG_FIFO_COUNTH, rx, 2)) {
hal.console->printf("MPU60x0: error in fifo read\n");
return;

View File

@ -108,10 +108,10 @@ private:
AP_MPU6000_AuxiliaryBus *_auxiliary_bus;
// is this an ICM-20608?
bool _is_icm_device:1;
bool _is_icm_device;
// are we doing more than 1kHz sampling?
bool _fast_sampling:1;
bool _fast_sampling;
// last time we read temperature
uint32_t _last_temp_read_ms;