Skip to content
Snippets Groups Projects
Commit 2f01dfe8 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

AP_InertialSensor: fixed from review by Lucas

parent 81b933d9
No related branches found
No related tags found
No related merge requests found
...@@ -568,8 +568,6 @@ void AP_InertialSensor_MPU6000::_read_fifo() ...@@ -568,8 +568,6 @@ void AP_InertialSensor_MPU6000::_read_fifo()
uint16_t bytes_read; uint16_t bytes_read;
uint8_t *rx = _fifo_buffer; 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)) { if (!_block_read(MPUREG_FIFO_COUNTH, rx, 2)) {
hal.console->printf("MPU60x0: error in fifo read\n"); hal.console->printf("MPU60x0: error in fifo read\n");
return; return;
......
...@@ -108,10 +108,10 @@ private: ...@@ -108,10 +108,10 @@ private:
AP_MPU6000_AuxiliaryBus *_auxiliary_bus; AP_MPU6000_AuxiliaryBus *_auxiliary_bus;
// is this an ICM-20608? // is this an ICM-20608?
bool _is_icm_device:1; bool _is_icm_device;
// are we doing more than 1kHz sampling? // are we doing more than 1kHz sampling?
bool _fast_sampling:1; bool _fast_sampling;
// last time we read temperature // last time we read temperature
uint32_t _last_temp_read_ms; uint32_t _last_temp_read_ms;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment