mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: Remove unused parameter
This commit is contained in:
parent
e66a360e27
commit
983356213a
|
@ -55,11 +55,7 @@ extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
// Class level parameters
|
// Class level parameters
|
||||||
const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
|
const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
|
||||||
// @Param: PRODUCT_ID
|
// 0 was PRODUCT_ID
|
||||||
// @DisplayName: IMU Product ID
|
|
||||||
// @Description: unused
|
|
||||||
// @User: Advanced
|
|
||||||
AP_GROUPINFO("PRODUCT_ID", 0, AP_InertialSensor, _old_product_id, 0),
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
The following parameter indexes and reserved from previous use
|
The following parameter indexes and reserved from previous use
|
||||||
|
|
|
@ -424,9 +424,6 @@ private:
|
||||||
uint16_t _accel_raw_sampling_multiplier[INS_MAX_INSTANCES];
|
uint16_t _accel_raw_sampling_multiplier[INS_MAX_INSTANCES];
|
||||||
uint16_t _gyro_raw_sampling_multiplier[INS_MAX_INSTANCES];
|
uint16_t _gyro_raw_sampling_multiplier[INS_MAX_INSTANCES];
|
||||||
|
|
||||||
// product id
|
|
||||||
AP_Int16 _old_product_id;
|
|
||||||
|
|
||||||
// IDs to uniquely identify each sensor: shall remain
|
// IDs to uniquely identify each sensor: shall remain
|
||||||
// the same across reboots
|
// the same across reboots
|
||||||
AP_Int32 _accel_id[INS_MAX_INSTANCES];
|
AP_Int32 _accel_id[INS_MAX_INSTANCES];
|
||||||
|
|
Loading…
Reference in New Issue