AP_InertialSensor: added simple_accel_cal()

this is useful for mass market vehicles where a full 3D accel cal is
too complex.
This commit is contained in:
Andrew Tridgell 2017-06-05 13:03:28 +10:00
parent 02586b0a2e
commit d5cab1140a
2 changed files with 166 additions and 0 deletions

View File

@ -8,6 +8,7 @@
#include <AP_Notify/AP_Notify.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_AHRS/AP_AHRS.h>
#include "AP_InertialSensor.h"
#include "AP_InertialSensor_BMI160.h"
@ -1746,3 +1747,164 @@ bool AP_InertialSensor::get_primary_accel_cal_sample_avg(uint8_t sample_num, Vec
ret.rotate(_board_orientation);
return true;
}
/*
perform a simple 1D accel calibration, returning mavlink result code
*/
uint8_t AP_InertialSensor::simple_accel_cal(AP_AHRS &ahrs)
{
uint8_t num_accels = MIN(get_accel_count(), INS_MAX_INSTANCES);
Vector3f last_average[INS_MAX_INSTANCES];
Vector3f new_accel_offset[INS_MAX_INSTANCES];
Vector3f saved_offsets[INS_MAX_INSTANCES];
Vector3f saved_scaling[INS_MAX_INSTANCES];
bool converged[INS_MAX_INSTANCES];
const float accel_convergence_limit = 0.05;
Vector3f rotated_gravity(0, 0, -GRAVITY_MSS);
// exit immediately if calibration is already in progress
if (_calibrating) {
return MAV_RESULT_TEMPORARILY_REJECTED;
}
// record we are calibrating
_calibrating = true;
// flash leds to tell user to keep the IMU still
AP_Notify::flags.initialising = true;
hal.console->printf("Simple accel cal");
/*
we do the accel calibration with no board rotation. This avoids
having to rotate readings during the calibration
*/
enum Rotation saved_orientation = _board_orientation;
_board_orientation = ROTATION_NONE;
// get the rotated gravity vector which will need to be applied to the offsets
rotated_gravity.rotate_inverse(saved_orientation);
// save existing accel offsets
for (uint8_t k=0; k<num_accels; k++) {
saved_offsets[k] = _accel_offset[k];
saved_scaling[k] = _accel_scale[k];
}
// remove existing accel offsets and scaling
for (uint8_t k=0; k<num_accels; k++) {
_accel_offset[k].set(Vector3f());
_accel_scale[k].set(Vector3f(1,1,1));
new_accel_offset[k].zero();
last_average[k].zero();
converged[k] = false;
}
for (uint8_t c = 0; c < 5; c++) {
hal.scheduler->delay(5);
update();
}
// the strategy is to average 50 points over 0.5 seconds, then do it
// again and see if the 2nd average is within a small margin of
// the first
uint8_t num_converged = 0;
// we try to get a good calibration estimate for up to 10 seconds
// if the accels are stable, we should get it in 1 second
for (int16_t j = 0; j <= 10*4 && num_converged < num_accels; j++) {
Vector3f accel_sum[INS_MAX_INSTANCES], accel_avg[INS_MAX_INSTANCES], accel_diff[INS_MAX_INSTANCES];
float diff_norm[INS_MAX_INSTANCES];
uint8_t i;
memset(diff_norm, 0, sizeof(diff_norm));
hal.console->printf("*");
for (uint8_t k=0; k<num_accels; k++) {
accel_sum[k].zero();
}
for (i=0; i<50; i++) {
update();
for (uint8_t k=0; k<num_accels; k++) {
accel_sum[k] += get_accel(k);
}
hal.scheduler->delay(5);
}
for (uint8_t k=0; k<num_accels; k++) {
accel_avg[k] = accel_sum[k] / i;
accel_diff[k] = last_average[k] - accel_avg[k];
diff_norm[k] = accel_diff[k].length();
}
for (uint8_t k=0; k<num_accels; k++) {
if (j > 0 && diff_norm[k] < accel_convergence_limit) {
last_average[k] = (accel_avg[k] * 0.5f) + (last_average[k] * 0.5f);
if (!converged[k] || last_average[k].length() < new_accel_offset[k].length()) {
new_accel_offset[k] = last_average[k];
}
if (!converged[k]) {
converged[k] = true;
num_converged++;
}
} else {
last_average[k] = accel_avg[k];
}
}
}
uint8_t result = MAV_RESULT_ACCEPTED;
// see if we've passed
for (uint8_t k=0; k<num_accels; k++) {
if (!converged[k]) {
result = MAV_RESULT_FAILED;
}
}
// restore orientation
_board_orientation = saved_orientation;
if (result == MAV_RESULT_ACCEPTED) {
hal.console->printf("\nPASSED\n");
for (uint8_t k=0; k<num_accels; k++) {
// remove rotated gravity
new_accel_offset[k] -= rotated_gravity;
_accel_offset[k].set_and_save(new_accel_offset[k]);
_accel_scale[k].save();
_accel_id[k].save();
_accel_id_ok[k] = true;
}
// force trim to zero
ahrs.set_trim(Vector3f(0, 0, 0));
} else {
hal.console->printf("\nFAILED\n");
// restore old values
for (uint8_t k=0; k<num_accels; k++) {
_accel_offset[k] = saved_offsets[k];
_accel_scale[k] = saved_scaling[k];
}
}
// record calibration complete
_calibrating = false;
// throw away any existing samples that may have the wrong
// orientation. We do this by throwing samples away for 0.5s,
// which is enough time for the filters to settle
uint32_t start_ms = AP_HAL::millis();
while (AP_HAL::millis() - start_ms < 500) {
update();
}
// and reset state estimators
ahrs.reset();
// stop flashing leds
AP_Notify::flags.initialising = false;
return result;
}

View File

@ -27,6 +27,7 @@
class AP_InertialSensor_Backend;
class AuxiliaryBus;
class AP_AHRS;
/*
forward declare DataFlash class. We can't include DataFlash.h
@ -263,6 +264,9 @@ public:
// update accel calibrator
void acal_update();
// simple accel calibration
uint8_t simple_accel_cal(AP_AHRS &ahrs);
bool accel_cal_requires_reboot() const { return _accel_cal_requires_reboot; }
// return time in microseconds of last update() call