From b650d397866a040b950709abd4dce24f6ea4bcae Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 21 Feb 2015 09:14:33 +0900 Subject: [PATCH] InertialSensor: remove product_id set to zero --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 4ce46e8bf6..bf0a9725bd 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -284,8 +284,6 @@ AP_InertialSensor::init( Start_style style, _detect_backends(); } - _product_id = 0; // FIX - // initialise accel scale if need be. This is needed as we can't // give non-zero default values for vectors in AP_Param for (uint8_t i=0; i