diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 6242c7ccdd..3042dc98a6 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -200,7 +200,7 @@ static int16_t spi_transfer_16(void) return (((int16_t)byte_H)<<8) | byte_L; } -void AP_InertialSensor_MPU6000::read() +void AP_InertialSensor_MPU6000::read(uint32_t ) { // We start a multibyte SPI read of sensors byte addr = MPUREG_ACCEL_XOUT_H | 0x80; // Set most significant bit diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h index 407a12331b..79bb96b091 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h @@ -33,7 +33,7 @@ class AP_InertialSensor_MPU6000 : public AP_InertialSensor uint32_t sample_time(); void reset_sample_time(); - static void read(); + static void read(uint32_t); static uint8_t register_read( uint8_t reg ); static void register_write( uint8_t reg, uint8_t val ); static void hardware_init();