/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #include "AP_InertialSensor.h" #include #include #include extern const AP_HAL::HAL& hal; #define SAMPLE_UNIT 1 // Class level parameters const AP_Param::GroupInfo AP_InertialSensor::var_info[] PROGMEM = { // @Param: PRODUCT_ID // @DisplayName: IMU Product ID // @Description: Which type of IMU is installed (read-only). // @User: Advanced // @Values: 0:Unknown,1:APM1-1280,2:APM1-2560,88:APM2,3:SITL,4:PX4v1,5:PX4v2,256:Flymaple,257:Linux AP_GROUPINFO("PRODUCT_ID", 0, AP_InertialSensor, _product_id, 0), // @Param: ACCSCAL_X // @DisplayName: Accelerometer scaling of X axis // @Description: Accelerometer scaling of X axis. Calculated during acceleration calibration routine // @Range: 0.8 1.2 // @User: Advanced // @Param: ACCSCAL_Y // @DisplayName: Accelerometer scaling of Y axis // @Description: Accelerometer scaling of Y axis Calculated during acceleration calibration routine // @Range: 0.8 1.2 // @User: Advanced // @Param: ACCSCAL_Z // @DisplayName: Accelerometer scaling of Z axis // @Description: Accelerometer scaling of Z axis Calculated during acceleration calibration routine // @Range: 0.8 1.2 // @User: Advanced AP_GROUPINFO("ACCSCAL", 1, AP_InertialSensor, _accel_scale[0], 0), // @Param: ACCOFFS_X // @DisplayName: Accelerometer offsets of X axis // @Description: Accelerometer offsets of X axis. This is setup using the acceleration calibration or level operations // @Units: m/s/s // @Range: -300 300 // @User: Advanced // @Param: ACCOFFS_Y // @DisplayName: Accelerometer offsets of Y axis // @Description: Accelerometer offsets of Y axis. This is setup using the acceleration calibration or level operations // @Units: m/s/s // @Range: -300 300 // @User: Advanced // @Param: ACCOFFS_Z // @DisplayName: Accelerometer offsets of Z axis // @Description: Accelerometer offsets of Z axis. This is setup using the acceleration calibration or level operations // @Units: m/s/s // @Range: -300 300 // @User: Advanced AP_GROUPINFO("ACCOFFS", 2, AP_InertialSensor, _accel_offset[0], 0), // @Param: GYROFFS_X // @DisplayName: Gyro offsets of X axis // @Description: Gyro sensor offsets of X axis. This is setup on each boot during gyro calibrations // @Units: rad/s // @User: Advanced // @Param: GYROFFS_Y // @DisplayName: Gyro offsets of Y axis // @Description: Gyro sensor offsets of Y axis. This is setup on each boot during gyro calibrations // @Units: rad/s // @User: Advanced // @Param: GYROFFS_Z // @DisplayName: Gyro offsets of Z axis // @Description: Gyro sensor offsets of Z axis. This is setup on each boot during gyro calibrations // @Units: rad/s // @User: Advanced AP_GROUPINFO("GYROFFS", 3, AP_InertialSensor, _gyro_offset[0], 0), // @Param: MPU6K_FILTER // @DisplayName: MPU6000 filter frequency // @Description: Filter frequency to ask the MPU6000 to apply to samples. This can be set to a lower value to try to cope with very high vibration levels in aircraft. The default value on ArduPlane, APMrover2 and ArduCopter is 20Hz. This option takes effect on the next reboot or gyro initialisation // @Units: Hz // @Values: 0:Default,5:5Hz,10:10Hz,20:20Hz,42:42Hz,98:98Hz // @User: Advanced AP_GROUPINFO("MPU6K_FILTER", 4, AP_InertialSensor, _mpu6000_filter, 0), #if INS_MAX_INSTANCES > 1 // @Param: ACC2SCAL_X // @DisplayName: Accelerometer2 scaling of X axis // @Description: Accelerometer2 scaling of X axis. Calculated during acceleration calibration routine // @Range: 0.8 1.2 // @User: Advanced // @Param: ACC2SCAL_Y // @DisplayName: Accelerometer2 scaling of Y axis // @Description: Accelerometer2 scaling of Y axis Calculated during acceleration calibration routine // @Range: 0.8 1.2 // @User: Advanced // @Param: ACC2SCAL_Z // @DisplayName: Accelerometer2 scaling of Z axis // @Description: Accelerometer2 scaling of Z axis Calculated during acceleration calibration routine // @Range: 0.8 1.2 // @User: Advanced AP_GROUPINFO("ACC2SCAL", 5, AP_InertialSensor, _accel_scale[1], 0), // @Param: ACC2OFFS_X // @DisplayName: Accelerometer2 offsets of X axis // @Description: Accelerometer2 offsets of X axis. This is setup using the acceleration calibration or level operations // @Units: m/s/s // @Range: -300 300 // @User: Advanced // @Param: ACC2OFFS_Y // @DisplayName: Accelerometer2 offsets of Y axis // @Description: Accelerometer2 offsets of Y axis. This is setup using the acceleration calibration or level operations // @Units: m/s/s // @Range: -300 300 // @User: Advanced // @Param: ACC2OFFS_Z // @DisplayName: Accelerometer2 offsets of Z axis // @Description: Accelerometer2 offsets of Z axis. This is setup using the acceleration calibration or level operations // @Units: m/s/s // @Range: -300 300 // @User: Advanced AP_GROUPINFO("ACC2OFFS", 6, AP_InertialSensor, _accel_offset[1], 0), // @Param: GYR2OFFS_X // @DisplayName: Gyro2 offsets of X axis // @Description: Gyro2 sensor offsets of X axis. This is setup on each boot during gyro calibrations // @Units: rad/s // @User: Advanced // @Param: GYR2OFFS_Y // @DisplayName: Gyro2 offsets of Y axis // @Description: Gyro2 sensor offsets of Y axis. This is setup on each boot during gyro calibrations // @Units: rad/s // @User: Advanced // @Param: GYR2OFFS_Z // @DisplayName: Gyro2 offsets of Z axis // @Description: Gyro2 sensor offsets of Z axis. This is setup on each boot during gyro calibrations // @Units: rad/s // @User: Advanced AP_GROUPINFO("GYR2OFFS", 7, AP_InertialSensor, _gyro_offset[1], 0), #endif #if INS_MAX_INSTANCES > 2 // @Param: ACC3SCAL_X // @DisplayName: Accelerometer3 scaling of X axis // @Description: Accelerometer3 scaling of X axis. Calculated during acceleration calibration routine // @Range: 0.8 1.2 // @User: Advanced // @Param: ACC3SCAL_Y // @DisplayName: Accelerometer3 scaling of Y axis // @Description: Accelerometer3 scaling of Y axis Calculated during acceleration calibration routine // @Range: 0.8 1.2 // @User: Advanced // @Param: ACC3SCAL_Z // @DisplayName: Accelerometer3 scaling of Z axis // @Description: Accelerometer3 scaling of Z axis Calculated during acceleration calibration routine // @Range: 0.8 1.2 // @User: Advanced AP_GROUPINFO("ACC3SCAL", 8, AP_InertialSensor, _accel_scale[2], 0), // @Param: ACC3OFFS_X // @DisplayName: Accelerometer3 offsets of X axis // @Description: Accelerometer3 offsets of X axis. This is setup using the acceleration calibration or level operations // @Units: m/s/s // @Range: -300 300 // @User: Advanced // @Param: ACC3OFFS_Y // @DisplayName: Accelerometer3 offsets of Y axis // @Description: Accelerometer3 offsets of Y axis. This is setup using the acceleration calibration or level operations // @Units: m/s/s // @Range: -300 300 // @User: Advanced // @Param: ACC3OFFS_Z // @DisplayName: Accelerometer3 offsets of Z axis // @Description: Accelerometer3 offsets of Z axis. This is setup using the acceleration calibration or level operations // @Units: m/s/s // @Range: -300 300 // @User: Advanced AP_GROUPINFO("ACC3OFFS", 9, AP_InertialSensor, _accel_offset[2], 0), // @Param: GYR3OFFS_X // @DisplayName: Gyro3 offsets of X axis // @Description: Gyro3 sensor offsets of X axis. This is setup on each boot during gyro calibrations // @Units: rad/s // @User: Advanced // @Param: GYR3OFFS_Y // @DisplayName: Gyro3 offsets of Y axis // @Description: Gyro3 sensor offsets of Y axis. This is setup on each boot during gyro calibrations // @Units: rad/s // @User: Advanced // @Param: GYR3OFFS_Z // @DisplayName: Gyro3 offsets of Z axis // @Description: Gyro3 sensor offsets of Z axis. This is setup on each boot during gyro calibrations // @Units: rad/s // @User: Advanced AP_GROUPINFO("GYR3OFFS", 10, AP_InertialSensor, _gyro_offset[2], 0), #endif AP_GROUPEND }; AP_InertialSensor::AP_InertialSensor() : _gyro_count(0), _accel_count(0), _backend_count(0), _accel(), _gyro(), _board_orientation(ROTATION_NONE), _hil_mode(false), _have_3D_calibration(false) { AP_Param::setup_object_defaults(this, var_info); for (uint8_t i=0; ipanic(PSTR("Too many gyros")); } return _gyro_count++; } /* register a new accel instance */ uint8_t AP_InertialSensor::register_accel(void) { if (_accel_count == INS_MAX_INSTANCES) { hal.scheduler->panic(PSTR("Too many accels")); } return _accel_count++; } void AP_InertialSensor::init( Start_style style, Sample_rate sample_rate) { // remember the sample rate _sample_rate = sample_rate; if (_gyro_count == 0 && _accel_count == 0) { // detect available backends. Only called once _detect_backends(); } _product_id = 0; // FIX // initialise accel scale if need be. This is needed as we can't // give non-zero default values for vectors in AP_Param for (uint8_t i=0; ipanic(PSTR("Too many INS backends")); } _backends[_backend_count] = detect(*this); if (_backends[_backend_count] != NULL) { _backend_count++; } } /* detect available backends for this board */ void AP_InertialSensor::_detect_backends(void) { #if HAL_INS_DEFAULT == HAL_INS_HIL _add_backend(AP_InertialSensor_HIL::detect); #elif HAL_INS_DEFAULT == HAL_INS_MPU6000 _add_backend(AP_InertialSensor_MPU6000::detect); #elif HAL_INS_DEFAULT == HAL_INS_PX4 || HAL_INS_DEFAULT == HAL_INS_VRBRAIN _add_backend(AP_InertialSensor_PX4::detect); #elif HAL_INS_DEFAULT == HAL_INS_OILPAN _add_backend(AP_InertialSensor_Oilpan::detect); #elif HAL_INS_DEFAULT == HAL_INS_MPU9250 _add_backend(AP_InertialSensor_MPU9250::detect); #elif HAL_INS_DEFAULT == HAL_INS_FLYMAPLE _add_backend(AP_InertialSensor_Flymaple::detect); #else #error Unrecognised HAL_INS_TYPE setting #endif #if 0 // disabled due to broken hardware on some PXF capes #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF // the PXF also has a MPU6000 _add_backend(AP_InertialSensor_MPU6000::detect); #endif #endif if (_backend_count == 0 || _gyro_count == 0 || _accel_count == 0) { hal.scheduler->panic(PSTR("No INS backends available")); } // set the product ID to the ID of the first backend _product_id.set(_backends[0]->product_id()); } void AP_InertialSensor::init_accel() { _init_accel(); // save calibration _save_parameters(); check_3D_calibration(); } #if !defined( __AVR_ATmega1280__ ) // calibrate_accel - perform accelerometer calibration including providing user // instructions and feedback Gauss-Newton accel calibration routines borrowed // from Rolfe Schmidt blog post describing the method: // http://chionophilous.wordpress.com/2011/10/24/accelerometer-calibration-iv-1-implementing-gauss-newton-on-an-atmega/ // original sketch available at // http://rolfeschmidt.com/mathtools/skimetrics/adxl_gn_calibration.pde bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact, float &trim_roll, float &trim_pitch) { uint8_t num_accels = min(get_accel_count(), INS_MAX_INSTANCES); Vector3f samples[INS_MAX_INSTANCES][6]; Vector3f new_offsets[INS_MAX_INSTANCES]; Vector3f new_scaling[INS_MAX_INSTANCES]; Vector3f orig_offset[INS_MAX_INSTANCES]; Vector3f orig_scale[INS_MAX_INSTANCES]; uint8_t num_ok = 0; for (uint8_t k=0; kprintf_P( PSTR("Place vehicle %S and press any key.\n"), msg); // wait for user input if (!interact->blocking_read()) { //No need to use interact->printf_P for an error, blocking_read does this when it fails goto failed; } // clear out any existing samples from ins update(); // average 32 samples for (uint8_t k=0; kdelay(10); num_samples++; } for (uint8_t k=0; kprintf_P(PSTR("Offsets[%u]: %.2f %.2f %.2f\n"), (unsigned)k, new_offsets[k].x, new_offsets[k].y, new_offsets[k].z); interact->printf_P(PSTR("Scaling[%u]: %.2f %.2f %.2f\n"), (unsigned)k, new_scaling[k].x, new_scaling[k].y, new_scaling[k].z); if (success) num_ok++; } if (num_ok == num_accels) { interact->printf_P(PSTR("Calibration successful\n")); for (uint8_t k=0; kprintf_P(PSTR("Calibration FAILED\n")); // restore original scaling and offsets for (uint8_t k=0; k 0); } // gyro_calibration_ok_all - returns true if all gyros were calibrated successfully bool AP_InertialSensor::gyro_calibrated_ok_all() const { for (uint8_t i=0; i 0); } // get_accel_health_all - return true if all accels are healthy bool AP_InertialSensor::get_accel_health_all(void) const { for (uint8_t i=0; i 0); } void AP_InertialSensor::_init_accel() { uint8_t num_accels = min(get_accel_count(), INS_MAX_INSTANCES); uint8_t flashcount = 0; Vector3f prev[INS_MAX_INSTANCES]; Vector3f accel_offset[INS_MAX_INSTANCES]; float total_change[INS_MAX_INSTANCES]; float max_offset[INS_MAX_INSTANCES]; memset(max_offset, 0, sizeof(max_offset)); memset(total_change, 0, sizeof(total_change)); // cold start hal.scheduler->delay(100); hal.console->print_P(PSTR("Init Accel")); // flash leds to tell user to keep the IMU still AP_Notify::flags.initialising = true; // clear accelerometer offsets and scaling for (uint8_t k=0; kdelay(20); update(); // low pass filter the offsets for (uint8_t k=0; k= 10) { hal.console->print_P(PSTR("*")); flashcount = 0; } flashcount++; } for (uint8_t k=0; k accel_offset[k].y) ? accel_offset[k].x : accel_offset[k].y; max_offset[k] = (max_offset[k] > accel_offset[k].z) ? max_offset[k] : accel_offset[k].z; } uint8_t num_converged = 0; for (uint8_t k=0; kdelay(500); } // set the global accel offsets for (uint8_t k=0; kprint_P(PSTR(" ")); } void 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]; float best_diff[INS_MAX_INSTANCES]; bool converged[INS_MAX_INSTANCES]; // cold start hal.console->print_P(PSTR("Init Gyro")); // flash leds to tell user to keep the IMU still AP_Notify::flags.initialising = true; // remove existing gyro offsets for (uint8_t k=0; kdelay(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 30 seconds // if the gyros are stable, we should get it in 1 second for (int16_t j = 0; j <= 30*4 && num_converged < num_gyros; j++) { Vector3f gyro_sum[INS_MAX_INSTANCES], gyro_avg[INS_MAX_INSTANCES], gyro_diff[INS_MAX_INSTANCES]; float diff_norm[INS_MAX_INSTANCES]; uint8_t i; memset(diff_norm, 0, sizeof(diff_norm)); hal.console->print_P(PSTR("*")); for (uint8_t k=0; kdelay(5); } for (uint8_t k=0; kprintln(); for (uint8_t k=0; kprintf_P(PSTR("gyro[%u] did not converge: diff=%f dps\n"), (unsigned)k, ToDeg(best_diff[k])); _gyro_offset[k] = best_avg[k]; // flag calibration as failed for this gyro _gyro_cal_ok[k] = false; } } } #if !defined( __AVR_ATmega1280__ ) // _calibrate_model - perform low level accel calibration // accel_sample are accelerometer samples collected in 6 different positions // accel_offsets are output from the calibration routine // accel_scale are output from the calibration routine // returns true if successful bool AP_InertialSensor::_calibrate_accel( Vector3f accel_sample[6], Vector3f& accel_offsets, Vector3f& accel_scale ) { int16_t i; int16_t num_iterations = 0; float eps = 0.000000001; float change = 100.0; float data[3]; float beta[6]; float delta[6]; float ds[6]; float JS[6][6]; bool success = true; // reset beta[0] = beta[1] = beta[2] = 0; beta[3] = beta[4] = beta[5] = 1.0f/GRAVITY_MSS; while( num_iterations < 20 && change > eps ) { num_iterations++; _calibrate_reset_matrices(ds, JS); for( i=0; i<6; i++ ) { data[0] = accel_sample[i].x; data[1] = accel_sample[i].y; data[2] = accel_sample[i].z; _calibrate_update_matrices(ds, JS, beta, data); } _calibrate_find_delta(ds, JS, delta); change = delta[0]*delta[0] + delta[0]*delta[0] + delta[1]*delta[1] + delta[2]*delta[2] + delta[3]*delta[3] / (beta[3]*beta[3]) + delta[4]*delta[4] / (beta[4]*beta[4]) + delta[5]*delta[5] / (beta[5]*beta[5]); for( i=0; i<6; i++ ) { beta[i] -= delta[i]; } } // copy results out accel_scale.x = beta[3] * GRAVITY_MSS; accel_scale.y = beta[4] * GRAVITY_MSS; accel_scale.z = beta[5] * GRAVITY_MSS; accel_offsets.x = beta[0] * accel_scale.x; accel_offsets.y = beta[1] * accel_scale.y; accel_offsets.z = beta[2] * accel_scale.z; // sanity check scale if( accel_scale.is_nan() || fabsf(accel_scale.x-1.0f) > 0.1f || fabsf(accel_scale.y-1.0f) > 0.1f || fabsf(accel_scale.z-1.0f) > 0.1f ) { success = false; } // sanity check offsets (3.5 is roughly 3/10th of a G, 5.0 is roughly half a G) if( accel_offsets.is_nan() || fabsf(accel_offsets.x) > 3.5f || fabsf(accel_offsets.y) > 3.5f || fabsf(accel_offsets.z) > 3.5f ) { success = false; } // return success or failure return success; } void AP_InertialSensor::_calibrate_update_matrices(float dS[6], float JS[6][6], float beta[6], float data[3]) { int16_t j, k; float dx, b; float residual = 1.0; float jacobian[6]; for( j=0; j<3; j++ ) { b = beta[3+j]; dx = (float)data[j] - beta[j]; residual -= b*b*dx*dx; jacobian[j] = 2.0f*b*b*dx; jacobian[3+j] = -2.0f*b*dx*dx; } for( j=0; j<6; j++ ) { dS[j] += jacobian[j]*residual; for( k=0; k<6; k++ ) { JS[j][k] += jacobian[j]*jacobian[k]; } } } // _calibrate_reset_matrices - clears matrices void AP_InertialSensor::_calibrate_reset_matrices(float dS[6], float JS[6][6]) { int16_t j,k; for( j=0; j<6; j++ ) { dS[j] = 0.0f; for( k=0; k<6; k++ ) { JS[j][k] = 0.0f; } } } void AP_InertialSensor::_calibrate_find_delta(float dS[6], float JS[6][6], float delta[6]) { //Solve 6-d matrix equation JS*x = dS //first put in upper triangular form int16_t i,j,k; float mu; //make upper triangular for( i=0; i<6; i++ ) { //eliminate all nonzero entries below JS[i][i] for( j=i+1; j<6; j++ ) { mu = JS[i][j]/JS[i][i]; if( mu != 0.0f ) { dS[j] -= mu*dS[i]; for( k=j; k<6; k++ ) { JS[k][j] -= mu*JS[k][i]; } } } } //back-substitute for( i=5; i>=0; i-- ) { dS[i] /= JS[i][i]; JS[i][i] = 1.0f; for( j=0; j 0 ) { trim_roll = -trim_roll; } if( scaled_accels_x.x < 0 ) { trim_pitch = -trim_pitch; } } #endif // __AVR_ATmega1280__ // save parameters to eeprom void AP_InertialSensor::_save_parameters() { _product_id.save(); for (uint8_t i=0; iupdate(); } // adjust health status if a sensor has a non-zero error count // but another sensor doesn't. bool have_zero_accel_error_count = false; bool have_zero_gyro_error_count = false; for (uint8_t i=0; imicros(); if (_next_sample_usec == 0 && _delta_time <= 0) { // this is the first call to wait_for_sample() _last_sample_usec = now - _sample_period_usec; _next_sample_usec = now + _sample_period_usec; goto check_sample; } // see how long it is till the next sample is due if (_next_sample_usec - now <=_sample_period_usec) { // we're ahead on time, schedule next sample at expected period uint32_t wait_usec = _next_sample_usec - now; if (wait_usec > 200) { hal.scheduler->delay_microseconds(wait_usec); } _next_sample_usec += _sample_period_usec; } else if (now - _next_sample_usec < _sample_period_usec/8) { // we've overshot, but only by a small amount, keep on // schedule with no delay _next_sample_usec += _sample_period_usec; } else { // we've overshot by a larger amount, re-zero scheduling with // no delay _next_sample_usec = now + _sample_period_usec; } check_sample: if (!_hil_mode) { // we also wait for at least one backend to have a sample of both // accel and gyro. This normally completes immediately. bool gyro_available = false; bool accel_available = false; while (!gyro_available || !accel_available) { for (uint8_t i=0; i<_backend_count; i++) { gyro_available |= _backends[i]->gyro_sample_available(); accel_available |= _backends[i]->accel_sample_available(); } if (!gyro_available || !accel_available) { hal.scheduler->delay_microseconds(100); } } } now = hal.scheduler->micros(); _delta_time = (now - _last_sample_usec) * 1.0e-6f; _last_sample_usec = now; #if 0 { static uint64_t delta_time_sum; static uint16_t counter; if (delta_time_sum == 0) { delta_time_sum = _sample_period_usec; } delta_time_sum += _delta_time * 1.0e6f; if (counter++ == 400) { counter = 0; hal.console->printf("now=%lu _delta_time_sum=%lu diff=%ld\n", (unsigned long)now, (unsigned long)delta_time_sum, (long)(now - delta_time_sum)); } } #endif _have_sample = true; } /* support for setting accel and gyro vectors, for use by HIL */ void AP_InertialSensor::set_accel(uint8_t instance, const Vector3f &accel) { if (_accel_count == 0) { // we haven't initialised yet return; } if (instance < INS_MAX_INSTANCES) { _accel[instance] = accel; _accel_healthy[instance] = true; if (_accel_count <= instance) { _accel_count = instance+1; } } } void AP_InertialSensor::set_gyro(uint8_t instance, const Vector3f &gyro) { if (_gyro_count == 0) { // we haven't initialised yet return; } if (instance < INS_MAX_INSTANCES) { _gyro[instance] = gyro; _gyro_healthy[instance] = true; if (_gyro_count <= instance) { _gyro_count = instance+1; _gyro_cal_ok[instance] = true; } } }