Skip to content

Commit

Permalink
AP_InertialSensor: fixed gyro calibration bug
Browse files Browse the repository at this point in the history
we must not update _gyro_offset[] until we have completed calibration
of that gyro, or we will end up using the new offsets when asking for
the raw gyro vector
  • Loading branch information
tridge authored and jschall committed Apr 10, 2015
1 parent acccf0b commit cabca8d
Showing 1 changed file with 5 additions and 2 deletions.
7 changes: 5 additions & 2 deletions libraries/AP_InertialSensor/AP_InertialSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -684,6 +684,7 @@ AP_InertialSensor::_init_gyro()
{
uint8_t num_gyros = min(get_gyro_count(), INS_MAX_INSTANCES);
Vector3f last_average[INS_MAX_INSTANCES], best_avg[INS_MAX_INSTANCES];
Vector3f new_gyro_offset[INS_MAX_INSTANCES];
float best_diff[INS_MAX_INSTANCES];
bool converged[INS_MAX_INSTANCES];

Expand Down Expand Up @@ -711,6 +712,7 @@ AP_InertialSensor::_init_gyro()
// remove existing gyro offsets
for (uint8_t k=0; k<num_gyros; k++) {
_gyro_offset[k].set(Vector3f());
new_gyro_offset[k].zero();
best_diff[k] = 0;
last_average[k].zero();
converged[k] = false;
Expand Down Expand Up @@ -773,8 +775,8 @@ AP_InertialSensor::_init_gyro()
} else if (gyro_diff[k].length() < ToRad(0.1f)) {
// we want the average to be within 0.1 bit, which is 0.04 degrees/s
last_average[k] = (gyro_avg[k] * 0.5f) + (last_average[k] * 0.5f);
if (!converged[k] || last_average[k].length() < _gyro_offset[k].get().length()) {
_gyro_offset[k] = last_average[k];
if (!converged[k] || last_average[k].length() < new_gyro_offset[k].length()) {
new_gyro_offset[k] = last_average[k];
}
if (!converged[k]) {
converged[k] = true;
Expand All @@ -800,6 +802,7 @@ AP_InertialSensor::_init_gyro()
_gyro_cal_ok[k] = false;
} else {
_gyro_cal_ok[k] = true;
_gyro_offset[k] = new_gyro_offset[k];
}
}

Expand Down

0 comments on commit cabca8d

Please sign in to comment.