diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp
index 42add3715cc72dbaa8a3831ec360de0a6e50aef8..5d80c792dc5cee74ffc57ecf1bcce301e2aeeeda 100644
--- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp
+++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp
@@ -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;
diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h
index e32348c78ce3e97b5c3500dccfbec079d727a2c5..21077febb0b5efa21a2920cd86ec1d5c5f6a4fc8 100644
--- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h
+++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h
@@ -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;