From ed653f8dbb54bfcb6ad8a058b16f1ff6f1f2c703 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Wed, 20 Jan 2016 18:55:43 -0200 Subject: [PATCH] AP_InertialSensor: MPU60x0: add comment about 8G/16G --- libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index a39750de9a..26579f6b6f 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -557,6 +557,8 @@ void AP_InertialSensor_MPU6000::start() _product_id = _register_read(MPUREG_PRODUCT_ID); //Serial.printf("Product_ID= 0x%x\n", (unsigned) _mpu6000_product_id); + // TODO: should be changed to 16G once we have a way to override the + // previous offsets if ((_product_id == MPU6000ES_REV_C4) || (_product_id == MPU6000ES_REV_C5) || (_product_id == MPU6000_REV_C4) ||