AP_InertialSensor: remove product_id

We only leave the parameter there for backward-compatibility. However
product id on the inertial sensor is not much useful since it's only
kept for the first instance.

A better implementation per-gyro and per-accel is needed in order to
avoid problems with sensors taking the offsets configured for another
sensor.
This commit is contained in:
Lucas De Marchi 2016-09-03 12:37:47 -03:00 committed by Andrew Tridgell
parent a6ac02b61f
commit ace61087a1
12 changed files with 9 additions and 43 deletions

View File

@ -55,10 +55,9 @@ extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
// @Param: PRODUCT_ID
// @DisplayName: IMU Product ID
// @Description: Which type of IMU is installed (read-only).
// @Description: unused
// @User: Advanced
// @Values: 0:Unknown,1:unused,2:unused,88:unused,3:SITL,4:PX4v1,5:PX4v2,256:unused,257:Linux
AP_GROUPINFO("PRODUCT_ID", 0, AP_InertialSensor, _product_id, 0),
AP_GROUPINFO("PRODUCT_ID", 0, AP_InertialSensor, _old_product_id, 0),
/*
The following parameter indexes and reserved from previous use
@ -656,9 +655,6 @@ AP_InertialSensor::detect_backends(void)
if (_backend_count == 0) {
AP_HAL::panic("No INS backends available");
}
// set the product ID to the ID of the first backend
_product_id.set(_backends[0]->product_id());
}
/*
@ -992,7 +988,6 @@ AP_InertialSensor::_init_gyro()
// save parameters to eeprom
void AP_InertialSensor::_save_parameters()
{
_product_id.save();
for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
_accel_scale[i].save();
_accel_offset[i].save();

View File

@ -319,7 +319,7 @@ private:
Vector3f _last_raw_gyro[INS_MAX_INSTANCES];
// product id
AP_Int16 _product_id;
AP_Int16 _old_product_id;
// accelerometer scaling and offsets
AP_Vector3f _accel_scale[INS_MAX_INSTANCES];

View File

@ -7,8 +7,7 @@
const extern AP_HAL::HAL& hal;
AP_InertialSensor_Backend::AP_InertialSensor_Backend(AP_InertialSensor &imu) :
_imu(imu),
_product_id(AP_PRODUCT_ID_NONE)
_imu(imu)
{
_sem = hal.util->new_semaphore();
}

View File

@ -64,11 +64,6 @@ public:
*/
virtual AuxiliaryBus *get_auxiliary_bus() { return nullptr; }
/*
return the product ID
*/
int16_t product_id(void) const { return _product_id; }
int16_t get_id() const { return _id; }
protected:
@ -121,9 +116,6 @@ protected:
// set gyro error_count
void _set_gyro_error_count(uint8_t instance, uint32_t error_count);
// backend should fill in its product ID from AP_PRODUCT_ID_*
int16_t _product_id;
// backend unique identifier or -1 if backend doesn't identify itself
int16_t _id = -1;

View File

@ -30,7 +30,6 @@ bool AP_InertialSensor_HIL::_init_sensor(void)
_imu.register_gyro(1200);
_imu.register_accel(1200);
_product_id = AP_PRODUCT_ID_NONE;
_imu.set_hil_mode();
return true;

View File

@ -390,7 +390,6 @@ AP_InertialSensor_LSM9DS0::AP_InertialSensor_LSM9DS0(AP_InertialSensor &imu,
, _drdy_pin_num_g(drdy_pin_num_g)
, _rotation(rotation)
{
_product_id = AP_PRODUCT_ID_NONE;
}
AP_InertialSensor_Backend *AP_InertialSensor_LSM9DS0::probe(AP_InertialSensor &_imu,

View File

@ -350,15 +350,15 @@ void AP_InertialSensor_MPU6000::start()
hal.scheduler->delay(1);
// read the product ID rev c has 1/2 the sensitivity of rev d
_product_id = _register_read(MPUREG_PRODUCT_ID);
uint8_t 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) ||
(_product_id == MPU6000_REV_C5)) {
if ((product_id == MPU6000ES_REV_C4) ||
(product_id == MPU6000ES_REV_C5) ||
(product_id == MPU6000_REV_C4) ||
(product_id == MPU6000_REV_C5)) {
// Accel scale 8g (4096 LSB/g)
// Rev C has different scaling than rev D
_register_write(MPUREG_ACCEL_CONFIG,1<<3);

View File

@ -302,8 +302,6 @@ void AP_InertialSensor_MPU9250::start()
_register_write(MPUREG_GYRO_CONFIG, BITS_GYRO_FS_2000DPS);
hal.scheduler->delay(1);
_product_id = AP_PRODUCT_ID_MPU9250;
// RM-MPU-9250A-00.pdf, pg. 15, select accel full scale 16g
_register_write(MPUREG_ACCEL_CONFIG,3<<3);

View File

@ -156,17 +156,6 @@ bool AP_InertialSensor_PX4::_init_sensor(void)
_accel_sample_time[i] = 1.0f / samplerate;
}
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
_product_id = AP_PRODUCT_ID_VRBRAIN;
#else
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
_product_id = AP_PRODUCT_ID_PX4_V2;
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V4)
_product_id = AP_PRODUCT_ID_PX4_V4;
#else
_product_id = AP_PRODUCT_ID_PX4;
#endif
#endif
return true;
}

View File

@ -36,8 +36,6 @@ bool AP_InertialSensor_QURT::init_sensor(void)
mpu9250_mag_buffer = new ObjectBuffer<mpu9x50_data>(20);
init_mpu9250();
_product_id = AP_PRODUCT_ID_MPU9250;
return true;
}

View File

@ -42,8 +42,6 @@ bool AP_InertialSensor_SITL::init_sensor(void)
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_SITL::timer_update, void));
_product_id = AP_PRODUCT_ID_NONE;
return true;
}

View File

@ -35,7 +35,6 @@ bool AP_InertialSensor_QFLIGHT::init_sensor(void)
accel_instance = _imu.register_accel(1000);
hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_InertialSensor_QFLIGHT::timer_update, void));
_product_id = AP_PRODUCT_ID_MPU9250;
return true;
}