Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_AHRS/AP_AHRS_DCM.cpp
Views: 1798
/*1* APM_AHRS_DCM.cpp2*3* AHRS system using DCM matrices4*5* Based on DCM code by Doug Weibel, Jordi Munoz and Jose Julio. DIYDrones.com6*7* Adapted for the general ArduPilot AHRS interface by Andrew Tridgell89This program is free software: you can redistribute it and/or modify10it under the terms of the GNU General Public License as published by11the Free Software Foundation, either version 3 of the License, or12(at your option) any later version.1314This program is distributed in the hope that it will be useful,15but WITHOUT ANY WARRANTY; without even the implied warranty of16MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the17GNU General Public License for more details.1819You should have received a copy of the GNU General Public License20along with this program. If not, see <http://www.gnu.org/licenses/>.21*/2223#include "AP_AHRS_config.h"2425#if AP_AHRS_DCM_ENABLED2627#include "AP_AHRS.h"28#include <AP_HAL/AP_HAL.h>29#include <GCS_MAVLink/GCS.h>30#include <AP_GPS/AP_GPS.h>31#include <AP_Baro/AP_Baro.h>32#include <AP_Compass/AP_Compass.h>33#include <AP_Logger/AP_Logger.h>34#include <AP_Vehicle/AP_Vehicle_Type.h>3536extern const AP_HAL::HAL& hal;3738// this is the speed in m/s above which we first get a yaw lock with39// the GPS40#define GPS_SPEED_MIN 34142// the limit (in degrees/second) beyond which we stop integrating43// omega_I. At larger spin rates the DCM PI controller can get 'dizzy'44// which results in false gyro drift. See45// http://gentlenav.googlecode.com/files/fastRotations.pdf46#define SPIN_RATE_LIMIT 204748// reset the current gyro drift estimate49// should be called if gyro offsets are recalculated50void51AP_AHRS_DCM::reset_gyro_drift(void)52{53_omega_I.zero();54_omega_I_sum.zero();55_omega_I_sum_time = 0;56}5758// run a full DCM update round59void60AP_AHRS_DCM::update()61{62AP_InertialSensor &_ins = AP::ins();6364// ask the IMU how much time this sensor reading represents65const float delta_t = _ins.get_delta_time();6667// if the update call took more than 0.2 seconds then discard it,68// otherwise we may move too far. This happens when arming motors69// in ArduCopter70if (delta_t > 0.2f) {71memset((void *)&_ra_sum[0], 0, sizeof(_ra_sum));72_ra_deltat = 0;73return;74}7576// Integrate the DCM matrix using gyro inputs77matrix_update();7879// Normalize the DCM matrix80normalize();8182// Perform drift correction83drift_correction(delta_t);8485// paranoid check for bad values in the DCM matrix86check_matrix();8788// calculate the euler angles and DCM matrix which will be used89// for high level navigation control. Apply trim such that a90// positive trim value results in a positive vehicle rotation91// about that axis (ie a negative offset)92_body_dcm_matrix = _dcm_matrix * AP::ahrs().get_rotation_vehicle_body_to_autopilot_body();93_body_dcm_matrix.to_euler(&roll, &pitch, &yaw);9495// pre-calculate some trig for CPU purposes:96_cos_yaw = cosf(yaw);97_sin_yaw = sinf(yaw);9899backup_attitude();100101// remember the last origin for fallback support102IGNORE_RETURN(AP::ahrs().get_origin(last_origin));103104#if HAL_LOGGING_ENABLED105const uint32_t now_ms = AP_HAL::millis();106if (now_ms - last_log_ms >= 100) {107// log DCM at 10Hz108last_log_ms = now_ms;109110// @LoggerMessage: DCM111// @Description: DCM Estimator Data112// @Field: TimeUS: Time since system startup113// @Field: Roll: estimated roll114// @Field: Pitch: estimated pitch115// @Field: Yaw: estimated yaw116// @Field: ErrRP: lowest estimated gyro drift error117// @Field: ErrYaw: difference between measured yaw and DCM yaw estimate118// @Field: VWN: wind velocity, to-the-North component119// @Field: VWE: wind velocity, to-the-East component120// @Field: VWD: wind velocity, Up-to-Down component121AP::logger().WriteStreaming(122"DCM",123"TimeUS," "Roll," "Pitch," "Yaw," "ErrRP," "ErrYaw," "VWN," "VWE," "VWD",124"s" "d" "d" "d" "d" "h" "n" "n" "n",125"F" "0" "0" "0" "0" "0" "0" "0" "0",126"Q" "f" "f" "f" "f" "f" "f" "f" "f",127AP_HAL::micros64(),128degrees(roll),129degrees(pitch),130wrap_360(degrees(yaw)),131get_error_rp(),132get_error_yaw(),133_wind.x,134_wind.y,135_wind.z136);137}138#endif // HAL_LOGGING_ENABLED139}140141void AP_AHRS_DCM::get_results(AP_AHRS_Backend::Estimates &results)142{143results.roll_rad = roll;144results.pitch_rad = pitch;145results.yaw_rad = yaw;146147results.dcm_matrix = _body_dcm_matrix;148results.gyro_estimate = _omega;149results.gyro_drift = _omega_I;150results.accel_ef = _accel_ef;151152results.location_valid = get_location(results.location);153}154155/*156backup attitude to persistent_data for use in watchdog reset157*/158void AP_AHRS_DCM::backup_attitude(void)159{160AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;161pd.roll_rad = roll;162pd.pitch_rad = pitch;163pd.yaw_rad = yaw;164}165166// update the DCM matrix using only the gyros167void AP_AHRS_DCM::matrix_update(void)168{169// use only the primary gyro so our bias estimate is valid, allowing us to return the right filtered gyro170// for rate controllers171const auto &_ins = AP::ins();172Vector3f delta_angle;173float dangle_dt;174if (_ins.get_delta_angle(delta_angle, dangle_dt) && dangle_dt > 0) {175_omega = delta_angle / dangle_dt;176_omega += _omega_I;177_dcm_matrix.rotate((_omega + _omega_P + _omega_yaw_P) * dangle_dt);178}179180// now update _omega from the filtered value from the primary IMU. We need to use181// the primary IMU as the notch filters will only be running on one IMU182183// note that we do not include the P terms in _omega. This is184// because the spin_rate is calculated from _omega.length(),185// and including the P terms would give positive feedback into186// the _P_gain() calculation, which can lead to a very large P187// value188_omega = _ins.get_gyro() + _omega_I;189}190191192/*193* reset the DCM matrix and omega. Used on ground start, and on194* extreme errors in the matrix195*/196void197AP_AHRS_DCM::reset(bool recover_eulers)198{199// reset the integration terms200_omega_I.zero();201_omega_P.zero();202_omega_yaw_P.zero();203_omega.zero();204205// if the caller wants us to try to recover to the current206// attitude then calculate the dcm matrix from the current207// roll/pitch/yaw values208if (hal.util->was_watchdog_reset() && AP_HAL::millis() < 10000) {209const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;210roll = pd.roll_rad;211pitch = pd.pitch_rad;212yaw = pd.yaw_rad;213_dcm_matrix.from_euler(roll, pitch, yaw);214GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Restored watchdog attitude %.0f %.0f %.0f",215degrees(roll), degrees(pitch), degrees(yaw));216} else if (recover_eulers && !isnan(roll) && !isnan(pitch) && !isnan(yaw)) {217_dcm_matrix.from_euler(roll, pitch, yaw);218} else {219220// Use the measured accel due to gravity to calculate an initial221// roll and pitch estimate222223AP_InertialSensor &_ins = AP::ins();224225// Get body frame accel vector226Vector3f initAccVec = _ins.get_accel();227uint8_t counter = 0;228229// the first vector may be invalid as the filter starts up230while ((initAccVec.length() < 9.0f || initAccVec.length() > 11) && counter++ < 20) {231_ins.wait_for_sample();232_ins.update();233initAccVec = _ins.get_accel();234}235236// normalise the acceleration vector237if (initAccVec.length() > 5.0f) {238// calculate initial pitch angle239pitch = atan2f(initAccVec.x, norm(initAccVec.y, initAccVec.z));240// calculate initial roll angle241roll = atan2f(-initAccVec.y, -initAccVec.z);242} else {243// If we can't use the accel vector, then align flat244roll = 0.0f;245pitch = 0.0f;246}247_dcm_matrix.from_euler(roll, pitch, 0);248249}250251// pre-calculate some trig for CPU purposes:252_cos_yaw = cosf(yaw);253_sin_yaw = sinf(yaw);254255_last_startup_ms = AP_HAL::millis();256}257258/*259* check the DCM matrix for pathological values260*/261void262AP_AHRS_DCM::check_matrix(void)263{264if (_dcm_matrix.is_nan()) {265//Serial.printf("ERROR: DCM matrix NAN\n");266AP_AHRS_DCM::reset(true);267return;268}269// some DCM matrix values can lead to an out of range error in270// the pitch calculation via asin(). These NaN values can271// feed back into the rest of the DCM matrix via the272// error_course value.273if (!(_dcm_matrix.c.x < 1.0f &&274_dcm_matrix.c.x > -1.0f)) {275// We have an invalid matrix. Force a normalisation.276normalize();277278if (_dcm_matrix.is_nan() ||279fabsf(_dcm_matrix.c.x) > 10.0) {280// See Issue #20284: regarding the selection of 10.0 for DCM reset281// This won't be lowered without evidence of an issue or mathematical proof & testing of a lower bound282283// normalisation didn't fix the problem! We're284// in real trouble. All we can do is reset285//Serial.printf("ERROR: DCM matrix error. _dcm_matrix.c.x=%f\n",286// _dcm_matrix.c.x);287AP_AHRS_DCM::reset(true);288}289}290}291292// renormalise one vector component of the DCM matrix293// this will return false if renormalization fails294bool295AP_AHRS_DCM::renorm(Vector3f const &a, Vector3f &result)296{297// numerical errors will slowly build up over time in DCM,298// causing inaccuracies. We can keep ahead of those errors299// using the renormalization technique from the DCM IMU paper300// (see equations 18 to 21).301302// For APM we don't bother with the taylor expansion303// optimisation from the paper as on our 2560 CPU the cost of304// the sqrt() is 44 microseconds, and the small time saving of305// the taylor expansion is not worth the potential of306// additional error buildup.307308// Note that we can get significant renormalisation values309// when we have a larger delta_t due to a glitch elsewhere in310// APM, such as a I2c timeout or a set of EEPROM writes. While311// we would like to avoid these if possible, if it does happen312// we don't want to compound the error by making DCM less313// accurate.314315const float renorm_val = 1.0f / a.length();316317// keep the average for reporting318_renorm_val_sum += renorm_val;319_renorm_val_count++;320321if (!(renorm_val < 2.0f && renorm_val > 0.5f)) {322// this is larger than it should get - log it as a warning323if (!(renorm_val < 1.0e6f && renorm_val > 1.0e-6f)) {324// we are getting values which are way out of325// range, we will reset the matrix and hope we326// can recover our attitude using drift327// correction before we hit the ground!328//Serial.printf("ERROR: DCM renormalisation error. renorm_val=%f\n",329// renorm_val);330return false;331}332}333334result = a * renorm_val;335return true;336}337338/*************************************************339* Direction Cosine Matrix IMU: Theory340* William Premerlani and Paul Bizard341*342* Numerical errors will gradually reduce the orthogonality conditions expressed by equation 5343* to approximations rather than identities. In effect, the axes in the two frames of reference no344* longer describe a rigid body. Fortunately, numerical error accumulates very slowly, so it is a345* simple matter to stay ahead of it.346* We call the process of enforcing the orthogonality conditions: renormalization.347*/348void349AP_AHRS_DCM::normalize(void)350{351const float error = _dcm_matrix.a * _dcm_matrix.b; // eq.18352353const Vector3f t0 = _dcm_matrix.a - (_dcm_matrix.b * (0.5f * error)); // eq.19354const Vector3f t1 = _dcm_matrix.b - (_dcm_matrix.a * (0.5f * error)); // eq.19355const Vector3f t2 = t0 % t1; // c= a x b // eq.20356357if (!renorm(t0, _dcm_matrix.a) ||358!renorm(t1, _dcm_matrix.b) ||359!renorm(t2, _dcm_matrix.c)) {360// Our solution is blowing up and we will force back361// to last euler angles362_last_failure_ms = AP_HAL::millis();363AP_AHRS_DCM::reset(true);364}365}366367368// produce a yaw error value. The returned value is proportional369// to sin() of the current heading error in earth frame370float371AP_AHRS_DCM::yaw_error_compass(Compass &compass)372{373const Vector3f &mag = compass.get_field();374// get the mag vector in the earth frame375Vector2f rb = _dcm_matrix.mulXY(mag);376377if (rb.length() < FLT_EPSILON) {378return 0.0f;379}380381rb.normalize();382if (rb.is_inf()) {383// not a valid vector384return 0.0f;385}386387// update vector holding earths magnetic field (if required)388if( !is_equal(_last_declination, compass.get_declination()) ) {389_last_declination = compass.get_declination();390_mag_earth.x = cosf(_last_declination);391_mag_earth.y = sinf(_last_declination);392}393394// calculate the error term in earth frame395// calculate the Z component of the cross product of rb and _mag_earth396return rb % _mag_earth;397}398399// the _P_gain raises the gain of the PI controller400// when we are spinning fast. See the fastRotations401// paper from Bill.402float403AP_AHRS_DCM::_P_gain(float spin_rate)404{405if (spin_rate < ToRad(50)) {406return 1.0f;407}408if (spin_rate > ToRad(500)) {409return 10.0f;410}411return spin_rate/ToRad(50);412}413414// _yaw_gain reduces the gain of the PI controller applied to heading errors415// when observability from change of velocity is good (eg changing speed or turning)416// This reduces unwanted roll and pitch coupling due to compass errors for planes.417// High levels of noise on _accel_ef will cause the gain to drop and could lead to418// increased heading drift during straight and level flight, however some gain is419// always available. TODO check the necessity of adding adjustable acc threshold420// and/or filtering accelerations before getting magnitude421float422AP_AHRS_DCM::_yaw_gain(void) const423{424const float VdotEFmag = _accel_ef.xy().length();425426if (VdotEFmag <= 4.0f) {427return 0.2f*(4.5f - VdotEFmag);428}429return 0.1f;430}431432433// return true if we have and should use GPS434bool AP_AHRS_DCM::have_gps(void) const435{436if (_gps_use == GPSUse::Disable || AP::gps().status() <= AP_GPS::NO_FIX) {437return false;438}439return true;440}441442/*443when we are getting the initial attitude we want faster gains so444that if the board starts upside down we quickly approach the right445attitude.446We don't want to keep those high gains for too long though as high P447gains cause slow gyro offset learning. So we keep the high gains for448a maximum of 20 seconds449*/450bool AP_AHRS_DCM::use_fast_gains(void) const451{452return !hal.util->get_soft_armed() && (AP_HAL::millis() - _last_startup_ms) < 20000U;453}454455456// return true if we should use the compass for yaw correction457bool AP_AHRS_DCM::use_compass(void)458{459const Compass &compass = AP::compass();460461if (!compass.use_for_yaw()) {462// no compass available463return false;464}465if (!AP::ahrs().get_fly_forward() || !have_gps()) {466// we don't have any alternative to the compass467return true;468}469if (AP::gps().ground_speed() < GPS_SPEED_MIN) {470// we are not going fast enough to use the GPS471return true;472}473474// if the current yaw differs from the GPS yaw by more than 45475// degrees and the estimated wind speed is less than 80% of the476// ground speed, then switch to GPS navigation. This will help477// prevent flyaways with very bad compass offsets478const float error = fabsf(wrap_180(degrees(yaw) - AP::gps().ground_course()));479if (error > 45 && _wind.length() < AP::gps().ground_speed()*0.8f) {480if (AP_HAL::millis() - _last_consistent_heading > 2000) {481// start using the GPS for heading if the compass has been482// inconsistent with the GPS for 2 seconds483return false;484}485} else {486_last_consistent_heading = AP_HAL::millis();487}488489// use the compass490return true;491}492493// return the quaternion defining the rotation from NED to XYZ (body) axes494bool AP_AHRS_DCM::get_quaternion(Quaternion &quat) const495{496quat.from_rotation_matrix(_dcm_matrix);497return true;498}499500// yaw drift correction using the compass or GPS501// this function produces the _omega_yaw_P vector, and also502// contributes to the _omega_I.z long term yaw drift estimate503void504AP_AHRS_DCM::drift_correction_yaw(void)505{506bool new_value = false;507float yaw_error;508float yaw_deltat;509510const AP_GPS &_gps = AP::gps();511512Compass &compass = AP::compass();513514#if COMPASS_CAL_ENABLED515if (compass.is_calibrating()) {516// don't do any yaw correction while calibrating517return;518}519#endif520521if (AP_AHRS_DCM::use_compass()) {522/*523we are using compass for yaw524*/525if (compass.last_update_usec() != _compass_last_update) {526yaw_deltat = (compass.last_update_usec() - _compass_last_update) * 1.0e-6f;527_compass_last_update = compass.last_update_usec();528// we force an additional compass read()529// here. This has the effect of throwing away530// the first compass value, which can be bad531if (!have_initial_yaw && compass.read()) {532const float heading = compass.calculate_heading(_dcm_matrix);533_dcm_matrix.from_euler(roll, pitch, heading);534_omega_yaw_P.zero();535have_initial_yaw = true;536}537new_value = true;538yaw_error = yaw_error_compass(compass);539540// also update the _gps_last_update, so if we later541// disable the compass due to significant yaw error we542// don't suddenly change yaw with a reset543_gps_last_update = _gps.last_fix_time_ms();544}545} else if (AP::ahrs().get_fly_forward() && have_gps()) {546/*547we are using GPS for yaw548*/549if (_gps.last_fix_time_ms() != _gps_last_update &&550_gps.ground_speed() >= GPS_SPEED_MIN) {551yaw_deltat = (_gps.last_fix_time_ms() - _gps_last_update) * 1.0e-3f;552_gps_last_update = _gps.last_fix_time_ms();553new_value = true;554const float gps_course_rad = ToRad(_gps.ground_course());555const float yaw_error_rad = wrap_PI(gps_course_rad - yaw);556yaw_error = sinf(yaw_error_rad);557558/* reset yaw to match GPS heading under any of the559following 3 conditions:5605611) if we have reached GPS_SPEED_MIN and have never had562yaw information before5635642) if the last time we got yaw information from the GPS565is more than 20 seconds ago, which means we may have566suffered from considerable gyro drift5675683) if we are over 3*GPS_SPEED_MIN (which means 9m/s)569and our yaw error is over 60 degrees, which means very570poor yaw. This can happen on bungee launch when the571operator pulls back the plane rapidly enough then on572release the GPS heading changes very rapidly573*/574if (!have_initial_yaw ||575yaw_deltat > 20 ||576(_gps.ground_speed() >= 3*GPS_SPEED_MIN && fabsf(yaw_error_rad) >= 1.047f)) {577// reset DCM matrix based on current yaw578_dcm_matrix.from_euler(roll, pitch, gps_course_rad);579_omega_yaw_P.zero();580have_initial_yaw = true;581yaw_error = 0;582}583}584}585586if (!new_value) {587// we don't have any new yaw information588// slowly decay _omega_yaw_P to cope with loss589// of our yaw source590_omega_yaw_P *= 0.97f;591return;592}593594// convert the error vector to body frame595const float error_z = _dcm_matrix.c.z * yaw_error;596597// the spin rate changes the P gain, and disables the598// integration at higher rates599const float spin_rate = _omega.length();600601// sanity check _kp_yaw602if (_kp_yaw < AP_AHRS_YAW_P_MIN) {603_kp_yaw.set(AP_AHRS_YAW_P_MIN);604}605606// update the proportional control to drag the607// yaw back to the right value. We use a gain608// that depends on the spin rate. See the fastRotations.pdf609// paper from Bill Premerlani610// We also adjust the gain depending on the rate of change of horizontal velocity which611// is proportional to how observable the heading is from the accelerations and GPS velocity612// The acceleration derived heading will be more reliable in turns than compass or GPS613614_omega_yaw_P.z = error_z * _P_gain(spin_rate) * _kp_yaw * _yaw_gain();615if (use_fast_gains()) {616_omega_yaw_P.z *= 8;617}618619// don't update the drift term if we lost the yaw reference620// for more than 2 seconds621if (yaw_deltat < 2.0f && spin_rate < ToRad(SPIN_RATE_LIMIT)) {622// also add to the I term623_omega_I_sum.z += error_z * _ki_yaw * yaw_deltat;624}625626_error_yaw = 0.8f * _error_yaw + 0.2f * fabsf(yaw_error);627}628629630/**631return an accel vector delayed by AHRS_ACCEL_DELAY samples for a632specific accelerometer instance633*/634Vector3f AP_AHRS_DCM::ra_delayed(uint8_t instance, const Vector3f &ra)635{636// get the old element, and then fill it with the new element637const Vector3f ret = _ra_delay_buffer[instance];638_ra_delay_buffer[instance] = ra;639if (ret.is_zero()) {640// use the current vector if the previous vector is exactly641// zero. This prevents an error on initialisation642return ra;643}644return ret;645}646647/* returns true if attitude should be corrected from GPS-derived648* velocity-deltas. We turn this off for Copter and other similar649* vehicles while the vehicle is disarmed to avoid the HUD bobbing650* around while the vehicle is disarmed.651*/652bool AP_AHRS_DCM::should_correct_centrifugal() const653{654#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduSub) || APM_BUILD_TYPE(APM_BUILD_Blimp)655return hal.util->get_soft_armed();656#endif657658return true;659}660661// perform drift correction. This function aims to update _omega_P and662// _omega_I with our best estimate of the short term and long term663// gyro error. The _omega_P value is what pulls our attitude solution664// back towards the reference vector quickly. The _omega_I term is an665// attempt to learn the long term drift rate of the gyros.666//667// This drift correction implementation is based on a paper668// by Bill Premerlani from here:669// http://gentlenav.googlecode.com/files/RollPitchDriftCompensation.pdf670void671AP_AHRS_DCM::drift_correction(float deltat)672{673Vector3f velocity;674uint32_t last_correction_time;675676// perform yaw drift correction if we have a new yaw reference677// vector678drift_correction_yaw();679680const AP_InertialSensor &_ins = AP::ins();681682// rotate accelerometer values into the earth frame683for (uint8_t i=0; i<_ins.get_accel_count(); i++) {684if (_ins.use_accel(i)) {685/*686by using get_delta_velocity() instead of get_accel() the687accel value is sampled over the right time delta for688each sensor, which prevents an aliasing effect689*/690Vector3f delta_velocity;691float delta_velocity_dt;692_ins.get_delta_velocity(i, delta_velocity, delta_velocity_dt);693if (delta_velocity_dt > 0) {694Vector3f accel_ef = _dcm_matrix * (delta_velocity / delta_velocity_dt);695// integrate the accel vector in the earth frame between GPS readings696_ra_sum[i] += accel_ef * deltat;697}698}699}700701// set _accel_ef_blended based on filtered accel702_accel_ef = _dcm_matrix * _ins.get_accel();703704// keep a sum of the deltat values, so we know how much time705// we have integrated over706_ra_deltat += deltat;707708const AP_GPS &_gps = AP::gps();709const bool fly_forward = AP::ahrs().get_fly_forward();710711if (!have_gps() ||712_gps.status() < AP_GPS::GPS_OK_FIX_3D ||713_gps.num_sats() < _gps_minsats) {714// no GPS, or not a good lock. From experience we need at715// least 6 satellites to get a really reliable velocity number716// from the GPS.717//718// As a fallback we use the fixed wing acceleration correction719// if we have an airspeed estimate (which we only have if720// _fly_forward is set), otherwise no correction721if (_ra_deltat < 0.2f) {722// not enough time has accumulated723return;724}725726float airspeed_TAS = _last_airspeed_TAS;727#if AP_AIRSPEED_ENABLED728if (airspeed_sensor_enabled()) {729airspeed_TAS = AP::airspeed()->get_airspeed() * get_EAS2TAS();730}731#endif732733// use airspeed to estimate our ground velocity in734// earth frame by subtracting the wind735velocity = _dcm_matrix.colx() * airspeed_TAS;736737// add in wind estimate738velocity += _wind;739740last_correction_time = AP_HAL::millis();741_have_gps_lock = false;742} else {743if (_gps.last_fix_time_ms() == _ra_sum_start) {744// we don't have a new GPS fix - nothing more to do745return;746}747velocity = _gps.velocity();748last_correction_time = _gps.last_fix_time_ms();749if (_have_gps_lock == false) {750// if we didn't have GPS lock in the last drift751// correction interval then set the velocities equal752_last_velocity = velocity;753}754_have_gps_lock = true;755756// keep last airspeed estimate for dead-reckoning purposes757Vector3f airspeed = velocity - _wind;758759// rotate vector to body frame760airspeed = _body_dcm_matrix.mul_transpose(airspeed);761762// take positive component in X direction. This mimics a pitot763// tube764_last_airspeed_TAS = MAX(airspeed.x, 0);765}766767if (have_gps()) {768// use GPS for positioning with any fix, even a 2D fix769_last_lat = _gps.location().lat;770_last_lng = _gps.location().lng;771_last_pos_ms = AP_HAL::millis();772_position_offset_north = 0;773_position_offset_east = 0;774775// once we have a single GPS lock, we can update using776// dead-reckoning from then on777_have_position = true;778} else {779// update dead-reckoning position estimate780_position_offset_north += velocity.x * _ra_deltat;781_position_offset_east += velocity.y * _ra_deltat;782}783784// see if this is our first time through - in which case we785// just setup the start times and return786if (_ra_sum_start == 0) {787_ra_sum_start = last_correction_time;788_last_velocity = velocity;789return;790}791792// equation 9: get the corrected acceleration vector in earth frame. Units793// are m/s/s794Vector3f GA_e(0.0f, 0.0f, -1.0f);795796if (_ra_deltat <= 0) {797// waiting for more data798return;799}800801bool using_gps_corrections = false;802float ra_scale = 1.0f/(_ra_deltat*GRAVITY_MSS);803804if (should_correct_centrifugal() && (_have_gps_lock || fly_forward)) {805const float v_scale = gps_gain.get() * ra_scale;806const Vector3f vdelta = (velocity - _last_velocity) * v_scale;807GA_e += vdelta;808GA_e.normalize();809if (GA_e.is_inf()) {810// wait for some non-zero acceleration information811_last_failure_ms = AP_HAL::millis();812return;813}814using_gps_corrections = true;815}816817// calculate the error term in earth frame.818// we do this for each available accelerometer then pick the819// accelerometer that leads to the smallest error term. This takes820// advantage of the different sample rates on different821// accelerometers to dramatically reduce the impact of aliasing822// due to harmonics of vibrations that match closely the sampling823// rate of our accelerometers. On the Pixhawk we have the LSM303D824// running at 800Hz and the MPU6000 running at 1kHz, by combining825// the two the effects of aliasing are greatly reduced.826Vector3f error[INS_MAX_INSTANCES];827float error_dirn[INS_MAX_INSTANCES];828Vector3f GA_b[INS_MAX_INSTANCES];829int8_t besti = -1;830float best_error = 0;831for (uint8_t i=0; i<_ins.get_accel_count(); i++) {832if (!_ins.get_accel_health(i)) {833// only use healthy sensors834continue;835}836_ra_sum[i] *= ra_scale;837838// get the delayed ra_sum to match the GPS lag839if (using_gps_corrections) {840GA_b[i] = ra_delayed(i, _ra_sum[i]);841} else {842GA_b[i] = _ra_sum[i];843}844if (GA_b[i].is_zero()) {845// wait for some non-zero acceleration information846continue;847}848GA_b[i].normalize();849if (GA_b[i].is_inf()) {850// wait for some non-zero acceleration information851continue;852}853error[i] = GA_b[i] % GA_e;854// Take dot product to catch case vectors are opposite sign and parallel855error_dirn[i] = GA_b[i] * GA_e;856const float error_length = error[i].length();857if (besti == -1 || error_length < best_error) {858besti = i;859best_error = error_length;860}861// Catch case where orientation is 180 degrees out862if (error_dirn[besti] < 0.0f) {863best_error = 1.0f;864}865866}867868if (besti == -1) {869// no healthy accelerometers!870_last_failure_ms = AP_HAL::millis();871return;872}873874_active_accel_instance = besti;875876#define YAW_INDEPENDENT_DRIFT_CORRECTION 0877#if YAW_INDEPENDENT_DRIFT_CORRECTION878// step 2 calculate earth_error_Z879const float earth_error_Z = error.z;880881// equation 10882const float tilt = GA_e.xy().length();883884// equation 11885const float theta = atan2f(GA_b[besti].y, GA_b[besti].x);886887// equation 12888const Vector3f GA_e2 = Vector3f(cosf(theta)*tilt, sinf(theta)*tilt, GA_e.z);889890// step 6891error = GA_b[besti] % GA_e2;892error.z = earth_error_Z;893#endif // YAW_INDEPENDENT_DRIFT_CORRECTION894895// to reduce the impact of two competing yaw controllers, we896// reduce the impact of the gps/accelerometers on yaw when we are897// flat, but still allow for yaw correction using the898// accelerometers at high roll angles as long as we have a GPS899if (AP_AHRS_DCM::use_compass()) {900if (have_gps() && is_equal(gps_gain.get(), 1.0f)) {901error[besti].z *= sinf(fabsf(roll));902} else {903error[besti].z = 0;904}905}906907// if ins is unhealthy then stop attitude drift correction and908// hope the gyros are OK for a while. Just slowly reduce _omega_P909// to prevent previous bad accels from throwing us off910if (!_ins.healthy()) {911error[besti].zero();912} else {913// convert the error term to body frame914error[besti] = _dcm_matrix.mul_transpose(error[besti]);915}916917if (error[besti].is_nan() || error[besti].is_inf()) {918// don't allow bad values919check_matrix();920_last_failure_ms = AP_HAL::millis();921return;922}923924_error_rp = 0.8f * _error_rp + 0.2f * best_error;925926// base the P gain on the spin rate927const float spin_rate = _omega.length();928929// sanity check _kp value930if (_kp < AP_AHRS_RP_P_MIN) {931_kp.set(AP_AHRS_RP_P_MIN);932}933934// we now want to calculate _omega_P and _omega_I. The935// _omega_P value is what drags us quickly to the936// accelerometer reading.937_omega_P = error[besti] * _P_gain(spin_rate) * _kp;938if (use_fast_gains()) {939_omega_P *= 8;940}941942if (fly_forward && _gps.status() >= AP_GPS::GPS_OK_FIX_2D &&943_gps.ground_speed() < GPS_SPEED_MIN &&944_ins.get_accel().x >= 7 &&945pitch > radians(-30) && pitch < radians(30)) {946// assume we are in a launch acceleration, and reduce the947// rp gain by 50% to reduce the impact of GPS lag on948// takeoff attitude when using a catapult949_omega_P *= 0.5f;950}951952// accumulate some integrator error953if (spin_rate < ToRad(SPIN_RATE_LIMIT)) {954_omega_I_sum += error[besti] * _ki * _ra_deltat;955_omega_I_sum_time += _ra_deltat;956}957958if (_omega_I_sum_time >= 5) {959// limit the rate of change of omega_I to the hardware960// reported maximum gyro drift rate. This ensures that961// short term errors don't cause a buildup of omega_I962// beyond the physical limits of the device963const float change_limit = AP::ins().get_gyro_drift_rate() * _omega_I_sum_time;964_omega_I_sum.x = constrain_float(_omega_I_sum.x, -change_limit, change_limit);965_omega_I_sum.y = constrain_float(_omega_I_sum.y, -change_limit, change_limit);966_omega_I_sum.z = constrain_float(_omega_I_sum.z, -change_limit, change_limit);967_omega_I += _omega_I_sum;968_omega_I_sum.zero();969_omega_I_sum_time = 0;970}971972// zero our accumulator ready for the next GPS step973memset((void *)&_ra_sum[0], 0, sizeof(_ra_sum));974_ra_deltat = 0;975_ra_sum_start = last_correction_time;976977// remember the velocity for next time978_last_velocity = velocity;979}980981982// update our wind speed estimate983void AP_AHRS_DCM::estimate_wind(void)984{985if (!AP::ahrs().get_wind_estimation_enabled()) {986return;987}988const Vector3f &velocity = _last_velocity;989990// this is based on the wind speed estimation code from MatrixPilot by991// Bill Premerlani. Adaption for ArduPilot by Jon Challinger992// See http://gentlenav.googlecode.com/files/WindEstimation.pdf993const Vector3f fuselageDirection = _dcm_matrix.colx();994const Vector3f fuselageDirectionDiff = fuselageDirection - _last_fuse;995const uint32_t now = AP_HAL::millis();996997// scrap our data and start over if we're taking too long to get a direction change998if (now - _last_wind_time > 10000) {999_last_wind_time = now;1000_last_fuse = fuselageDirection;1001_last_vel = velocity;1002return;1003}10041005float diff_length = fuselageDirectionDiff.length();1006if (diff_length > 0.2f) {1007// when turning, use the attitude response to estimate1008// wind speed1009const Vector3f velocityDiff = velocity - _last_vel;10101011// estimate airspeed it using equation 61012const float V = velocityDiff.length() / diff_length;10131014const Vector3f fuselageDirectionSum = fuselageDirection + _last_fuse;1015const Vector3f velocitySum = velocity + _last_vel;10161017_last_fuse = fuselageDirection;1018_last_vel = velocity;10191020const float theta = atan2f(velocityDiff.y, velocityDiff.x) - atan2f(fuselageDirectionDiff.y, fuselageDirectionDiff.x);1021const float sintheta = sinf(theta);1022const float costheta = cosf(theta);10231024Vector3f wind{1025velocitySum.x - V * (costheta * fuselageDirectionSum.x - sintheta * fuselageDirectionSum.y),1026velocitySum.y - V * (sintheta * fuselageDirectionSum.x + costheta * fuselageDirectionSum.y),1027velocitySum.z - V * fuselageDirectionSum.z1028};1029wind *= 0.5f;10301031if (wind.length() < _wind.length() + 20) {1032_wind = _wind * 0.95f + wind * 0.05f;1033}10341035_last_wind_time = now;10361037return;1038}10391040#if AP_AIRSPEED_ENABLED1041if (now - _last_wind_time > 2000 && airspeed_sensor_enabled()) {1042// when flying straight use airspeed to get wind estimate if available1043const Vector3f airspeed = _dcm_matrix.colx() * AP::airspeed()->get_airspeed();1044const Vector3f wind = velocity - (airspeed * get_EAS2TAS());1045_wind = _wind * 0.92f + wind * 0.08f;1046}1047#endif1048}10491050#ifdef AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED1051void AP_AHRS_DCM::set_external_wind_estimate(float speed, float direction) {1052_wind.x = -cosf(radians(direction)) * speed;1053_wind.y = -sinf(radians(direction)) * speed;1054_wind.z = 0;1055}1056#endif10571058// return our current position estimate using1059// dead-reckoning or GPS1060bool AP_AHRS_DCM::get_location(Location &loc) const1061{1062loc.lat = _last_lat;1063loc.lng = _last_lng;1064const auto &baro = AP::baro();1065const auto &gps = AP::gps();1066if (_gps_use == GPSUse::EnableWithHeight &&1067gps.status() >= AP_GPS::GPS_OK_FIX_3D) {1068loc.alt = gps.location().alt;1069} else {1070loc.alt = baro.get_altitude() * 100 + AP::ahrs().get_home().alt;1071}1072loc.relative_alt = 0;1073loc.terrain_alt = 0;1074loc.offset(_position_offset_north, _position_offset_east);1075if (_have_position) {1076const uint32_t now = AP_HAL::millis();1077float dt = 0;1078gps.get_lag(dt);1079dt += constrain_float((now - _last_pos_ms) * 0.001, 0, 0.5);1080Vector2f dpos = _last_velocity.xy() * dt;1081loc.offset(dpos.x, dpos.y);1082}1083return _have_position;1084}10851086bool AP_AHRS_DCM::airspeed_EAS(float &airspeed_ret) const1087{1088#if AP_AIRSPEED_ENABLED1089const auto *airspeed = AP::airspeed();1090if (airspeed != nullptr) {1091return airspeed_EAS(airspeed->get_primary(), airspeed_ret);1092}1093#endif1094// airspeed_estimate will also make this nullptr check and act1095// appropriately when we call it with a dummy sensor ID.1096return airspeed_EAS(0, airspeed_ret);1097}10981099// return an (equivalent) airspeed estimate:1100// - from a real sensor if available1101// - otherwise from a GPS-derived wind-triangle estimate (if GPS available)1102// - otherwise from a cached wind-triangle estimate value (but returning false)1103bool AP_AHRS_DCM::airspeed_EAS(uint8_t airspeed_index, float &airspeed_ret) const1104{1105// airspeed_ret: will always be filled-in by get_unconstrained_airspeed_EAS which fills in airspeed_ret in this order:1106// airspeed as filled-in by an enabled airspeed sensor1107// if no airspeed sensor: airspeed estimated using the GPS speed & wind_speed_estimation1108// Or if none of the above, fills-in using the previous airspeed estimate1109// Return false: if we are using the previous airspeed estimate1110if (!get_unconstrained_airspeed_EAS(airspeed_index, airspeed_ret)) {1111return false;1112}11131114const float _wind_max = AP::ahrs().get_max_wind();1115if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {1116// constrain the airspeed by the ground speed1117// and AHRS_WIND_MAX1118const float gnd_speed = AP::gps().ground_speed();1119float true_airspeed = airspeed_ret * get_EAS2TAS();1120true_airspeed = constrain_float(true_airspeed,1121gnd_speed - _wind_max,1122gnd_speed + _wind_max);1123airspeed_ret = true_airspeed / get_EAS2TAS();1124}11251126return true;1127}11281129// airspeed_ret: will always be filled-in by get_unconstrained_airspeed_EAS which fills in airspeed_ret in this order:1130// airspeed as filled-in by an enabled airspeed sensor1131// if no airspeed sensor: airspeed estimated using the GPS speed & wind_speed_estimation1132// Or if none of the above, fills-in using the previous airspeed estimate1133// Return false: if we are using the previous airspeed estimate1134bool AP_AHRS_DCM::get_unconstrained_airspeed_EAS(uint8_t airspeed_index, float &airspeed_ret) const1135{1136#if AP_AIRSPEED_ENABLED1137if (airspeed_sensor_enabled(airspeed_index)) {1138airspeed_ret = AP::airspeed()->get_airspeed(airspeed_index);1139return true;1140}1141#endif11421143if (AP::ahrs().get_wind_estimation_enabled() && have_gps()) {1144// estimated via GPS speed and wind1145airspeed_ret = _last_airspeed_TAS * get_TAS2EAS();1146return true;1147}11481149// Else give the last estimate, but return false.1150// This is used by the dead-reckoning code1151airspeed_ret = _last_airspeed_TAS * get_TAS2EAS();1152return false;1153}11541155/*1156check if the AHRS subsystem is healthy1157*/1158bool AP_AHRS_DCM::healthy(void) const1159{1160// consider ourselves healthy if there have been no failures for 5 seconds1161return (_last_failure_ms == 0 || AP_HAL::millis() - _last_failure_ms > 5000);1162}11631164/*1165return NED velocity if we have GPS lock1166*/1167bool AP_AHRS_DCM::get_velocity_NED(Vector3f &vec) const1168{1169const AP_GPS &_gps = AP::gps();1170if (_gps.status() < AP_GPS::GPS_OK_FIX_3D) {1171return false;1172}1173vec = _gps.velocity();1174return true;1175}11761177// return a ground speed estimate in m/s1178Vector2f AP_AHRS_DCM::groundspeed_vector(void)1179{1180// Generate estimate of ground speed vector using air data system1181Vector2f gndVelADS;1182Vector2f gndVelGPS;1183float airspeed = 0;1184const bool gotAirspeed = airspeed_TAS(airspeed);1185const bool gotGPS = (AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D);1186if (gotAirspeed) {1187const Vector2f airspeed_vector{_cos_yaw * airspeed, _sin_yaw * airspeed};1188Vector3f wind;1189UNUSED_RESULT(wind_estimate(wind));1190gndVelADS = airspeed_vector + wind.xy();1191}11921193// Generate estimate of ground speed vector using GPS1194if (gotGPS) {1195const float cog = radians(AP::gps().ground_course());1196gndVelGPS = Vector2f(cosf(cog), sinf(cog)) * AP::gps().ground_speed();1197}1198// If both ADS and GPS data is available, apply a complementary filter1199if (gotAirspeed && gotGPS) {1200// The LPF is applied to the GPS and the HPF is applied to the air data estimate1201// before the two are summed1202//Define filter coefficients1203// alpha and beta must sum to one1204// beta = dt/Tau, where1205// dt = filter time step (0.1 sec if called by nav loop)1206// Tau = cross-over time constant (nominal 2 seconds)1207// More lag on GPS requires Tau to be bigger, less lag allows it to be smaller1208// To-Do - set Tau as a function of GPS lag.1209const float alpha = 1.0f - beta;1210// Run LP filters1211_lp = gndVelGPS * beta + _lp * alpha;1212// Run HP filters1213_hp = (gndVelADS - _lastGndVelADS) + _hp * alpha;1214// Save the current ADS ground vector for the next time step1215_lastGndVelADS = gndVelADS;1216// Sum the HP and LP filter outputs1217return _hp + _lp;1218}1219// Only ADS data is available return ADS estimate1220if (gotAirspeed && !gotGPS) {1221return gndVelADS;1222}1223// Only GPS data is available so return GPS estimate1224if (!gotAirspeed && gotGPS) {1225return gndVelGPS;1226}12271228if (airspeed > 0) {1229// we have a rough airspeed, and we have a yaw. For1230// dead-reckoning purposes we can create a estimated1231// groundspeed vector1232Vector2f ret{_cos_yaw, _sin_yaw};1233ret *= airspeed;1234// adjust for estimated wind1235Vector3f wind;1236UNUSED_RESULT(wind_estimate(wind));1237ret.x += wind.x;1238ret.y += wind.y;1239return ret;1240}12411242return Vector2f(0.0f, 0.0f);1243}12441245// Get a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.1246// This is different to the vertical velocity from the EKF which is not always consistent with the vertical position due to the various errors that are being corrected for.1247bool AP_AHRS_DCM::get_vert_pos_rate_D(float &velocity) const1248{1249Vector3f velned;1250if (get_velocity_NED(velned)) {1251velocity = velned.z;1252return true;1253} else if (AP::baro().healthy()) {1254velocity = -AP::baro().get_climb_rate();1255return true;1256}1257return false;1258}12591260// returns false if we fail arming checks, in which case the buffer will be populated with a failure message1261// requires_position should be true if horizontal position configuration should be checked (not used)1262bool AP_AHRS_DCM::pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const1263{1264if (!healthy()) {1265hal.util->snprintf(failure_msg, failure_msg_len, "Not healthy");1266return false;1267}1268return true;1269}12701271/*1272relative-origin functions for fallback in AP_InertialNav1273*/1274bool AP_AHRS_DCM::get_origin(Location &ret) const1275{1276ret = last_origin;1277if (ret.is_zero()) {1278// use home if we never have had an origin1279ret = AP::ahrs().get_home();1280}1281return !ret.is_zero();1282}12831284bool AP_AHRS_DCM::get_relative_position_NED_origin(Vector3f &posNED) const1285{1286Location origin;1287if (!AP_AHRS_DCM::get_origin(origin)) {1288return false;1289}1290Location loc;1291if (!AP_AHRS_DCM::get_location(loc)) {1292return false;1293}1294posNED = origin.get_distance_NED(loc);1295return true;1296}12971298bool AP_AHRS_DCM::get_relative_position_NE_origin(Vector2f &posNE) const1299{1300Vector3f posNED;1301if (!AP_AHRS_DCM::get_relative_position_NED_origin(posNED)) {1302return false;1303}1304posNE = posNED.xy();1305return true;1306}13071308bool AP_AHRS_DCM::get_relative_position_D_origin(float &posD) const1309{1310Vector3f posNED;1311if (!AP_AHRS_DCM::get_relative_position_NED_origin(posNED)) {1312return false;1313}1314posD = posNED.z;1315return true;1316}13171318void AP_AHRS_DCM::send_ekf_status_report(GCS_MAVLINK &link) const1319{1320}13211322// return true if DCM has a yaw source available1323bool AP_AHRS_DCM::yaw_source_available(void) const1324{1325return AP::compass().use_for_yaw();1326}13271328void AP_AHRS_DCM::get_control_limits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const1329{1330// lower gains in VTOL controllers when flying on DCM1331ekfGndSpdLimit = 50.0;1332ekfNavVelGainScaler = 0.5;1333}13341335#endif // AP_AHRS_DCM_ENABLED133613371338