mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
AP_InertialSensor: make max_abs_offsets a single float, not a vector
This commit is contained in:
parent
0fcd98c804
commit
ac3200fd32
@ -302,7 +302,7 @@ AP_InertialSensor::AP_InertialSensor() :
|
||||
_accel_clip_count[i] = 0;
|
||||
#endif
|
||||
|
||||
_accel_max_abs_offsets[i] = Vector3f(3.5f, 3.5f, 3.5f);
|
||||
_accel_max_abs_offsets[i] = 3.5f;
|
||||
}
|
||||
memset(_delta_velocity_valid,0,sizeof(_delta_velocity_valid));
|
||||
memset(_delta_angle_valid,0,sizeof(_delta_angle_valid));
|
||||
@ -987,7 +987,7 @@ bool AP_InertialSensor::_check_sample_range(const Vector3f accel_sample[6], enum
|
||||
bool AP_InertialSensor::_calibrate_accel(const Vector3f accel_sample[6],
|
||||
Vector3f& accel_offsets,
|
||||
Vector3f& accel_scale,
|
||||
Vector3f& max_abs_offsets,
|
||||
float max_abs_offsets,
|
||||
enum Rotation rotation)
|
||||
{
|
||||
int16_t i;
|
||||
@ -1046,9 +1046,9 @@ bool AP_InertialSensor::_calibrate_accel(const Vector3f accel_sample[6],
|
||||
}
|
||||
|
||||
if (accel_offsets.is_nan() ||
|
||||
fabsf(accel_offsets.x) > max_abs_offsets.x ||
|
||||
fabsf(accel_offsets.y) > max_abs_offsets.y ||
|
||||
fabsf(accel_offsets.z) > max_abs_offsets.z) {
|
||||
fabsf(accel_offsets.x) > max_abs_offsets ||
|
||||
fabsf(accel_offsets.y) > max_abs_offsets ||
|
||||
fabsf(accel_offsets.z) > max_abs_offsets) {
|
||||
success = false;
|
||||
}
|
||||
|
||||
|
@ -251,7 +251,7 @@ private:
|
||||
bool _calibrate_accel(const Vector3f accel_sample[6],
|
||||
Vector3f& accel_offsets,
|
||||
Vector3f& accel_scale,
|
||||
Vector3f& max_abs_offsets,
|
||||
float max_abs_offsets,
|
||||
enum Rotation rotation);
|
||||
bool _check_sample_range(const Vector3f accel_sample[6], enum Rotation rotation,
|
||||
AP_InertialSensor_UserInteract* interact);
|
||||
@ -297,7 +297,7 @@ private:
|
||||
AP_Vector3f _gyro_offset[INS_MAX_INSTANCES];
|
||||
|
||||
// accelerometer max absolute offsets to be used for calibration
|
||||
Vector3f _accel_max_abs_offsets[INS_MAX_INSTANCES];
|
||||
float _accel_max_abs_offsets[INS_MAX_INSTANCES];
|
||||
|
||||
// temperatures for an instance if available
|
||||
float _temperature[INS_MAX_INSTANCES];
|
||||
|
@ -79,9 +79,9 @@ void AP_InertialSensor_Backend::_publish_accel(uint8_t instance, const Vector3f
|
||||
}
|
||||
|
||||
void AP_InertialSensor_Backend::_set_accel_max_abs_offset(uint8_t instance,
|
||||
const Vector3f offset)
|
||||
float max_offset)
|
||||
{
|
||||
_imu._accel_max_abs_offsets[instance] = offset;
|
||||
_imu._accel_max_abs_offsets[instance] = max_offset;
|
||||
}
|
||||
|
||||
// set accelerometer error_count
|
||||
|
@ -74,7 +74,7 @@ protected:
|
||||
void _publish_accel(uint8_t instance, const Vector3f &accel, bool rotate_and_correct = true);
|
||||
|
||||
// set accelerometer max absolute offset for calibration
|
||||
void _set_accel_max_abs_offset(uint8_t instance, const Vector3f offset);
|
||||
void _set_accel_max_abs_offset(uint8_t instance, float offset);
|
||||
|
||||
// publish a temperature value
|
||||
void _publish_temperature(uint8_t instance, float temperature);
|
||||
|
@ -483,7 +483,7 @@ bool AP_InertialSensor_LSM9DS0::_init_sensor()
|
||||
_gyro_instance = _imu.register_gyro();
|
||||
_accel_instance = _imu.register_accel();
|
||||
|
||||
_set_accel_max_abs_offset(_accel_instance, Vector3f(5.0f, 5.0f, 5.0f));
|
||||
_set_accel_max_abs_offset(_accel_instance, 5.0f);
|
||||
|
||||
#if LSM9DS0_DEBUG
|
||||
_dump_registers();
|
||||
|
Loading…
Reference in New Issue
Block a user