12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139 |
- #include "AP_AHRS.h"
- #include <AP_HAL/AP_HAL.h>
- #include <GCS_MAVLink/GCS.h>
- #include <AP_GPS/AP_GPS.h>
- #include <AP_Baro/AP_Baro.h>
- extern const AP_HAL::HAL& hal;
- #define GPS_SPEED_MIN 3
- #define SPIN_RATE_LIMIT 20
- void
- AP_AHRS_DCM::reset_gyro_drift(void)
- {
- _omega_I.zero();
- _omega_I_sum.zero();
- _omega_I_sum_time = 0;
- }
- void AP_AHRS_DCM::load_watchdog_home()
- {
- const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
- if (hal.util->was_watchdog_reset() && (pd.home_lat != 0 || pd.home_lon != 0)) {
- _home.lat = pd.home_lat;
- _home.lng = pd.home_lon;
- _home.set_alt_cm(pd.home_alt_cm, Location::AltFrame::ABSOLUTE);
- _home_is_set = true;
- _home_locked = true;
- gcs().send_text(MAV_SEVERITY_INFO, "Restored watchdog home");
- }
- }
- void
- AP_AHRS_DCM::update(bool skip_ins_update)
- {
-
- WITH_SEMAPHORE(_rsem);
-
- float delta_t;
- if (_last_startup_ms == 0) {
- _last_startup_ms = AP_HAL::millis();
- load_watchdog_home();
- }
- if (!skip_ins_update) {
-
- AP::ins().update();
- }
- const AP_InertialSensor &_ins = AP::ins();
-
- delta_t = _ins.get_delta_time();
-
-
-
- if (delta_t > 0.2f) {
- memset((void *)&_ra_sum[0], 0, sizeof(_ra_sum));
- _ra_deltat = 0;
- return;
- }
-
- matrix_update(delta_t);
-
- normalize();
-
- drift_correction(delta_t);
-
- check_matrix();
-
- euler_angles();
-
- update_trig();
-
- update_AOA_SSA();
- backup_attitude();
- }
- void AP_AHRS_DCM::backup_attitude(void)
- {
- AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
- pd.roll_rad = roll;
- pd.pitch_rad = pitch;
- pd.yaw_rad = yaw;
- }
- void
- AP_AHRS_DCM::matrix_update(float _G_Dt)
- {
-
-
-
-
-
- _omega.zero();
-
-
-
-
- uint8_t healthy_count = 0;
- Vector3f delta_angle;
- const AP_InertialSensor &_ins = AP::ins();
- for (uint8_t i=0; i<_ins.get_gyro_count(); i++) {
- if (_ins.use_gyro(i) && healthy_count < 2) {
- Vector3f dangle;
- if (_ins.get_delta_angle(i, dangle)) {
- healthy_count++;
- delta_angle += dangle;
- }
- }
- }
- if (healthy_count > 1) {
- delta_angle /= healthy_count;
- }
- if (_G_Dt > 0) {
- _omega = delta_angle / _G_Dt;
- _omega += _omega_I;
- _dcm_matrix.rotate((_omega + _omega_P + _omega_yaw_P) * _G_Dt);
- }
- }
- void
- AP_AHRS_DCM::reset(bool recover_eulers)
- {
-
- WITH_SEMAPHORE(_rsem);
-
-
- _omega_I.zero();
- _omega_P.zero();
- _omega_yaw_P.zero();
- _omega.zero();
-
-
-
- if (hal.util->was_watchdog_reset() && AP_HAL::millis() < 10000) {
- const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
- roll = pd.roll_rad;
- pitch = pd.pitch_rad;
- yaw = pd.yaw_rad;
- _dcm_matrix.from_euler(roll, pitch, yaw);
- gcs().send_text(MAV_SEVERITY_INFO, "Restored watchdog attitude %.0f %.0f %.0f",
- degrees(roll), degrees(pitch), degrees(yaw));
- } else if (recover_eulers && !isnan(roll) && !isnan(pitch) && !isnan(yaw)) {
- _dcm_matrix.from_euler(roll, pitch, yaw);
- } else {
-
-
- AP_InertialSensor &_ins = AP::ins();
-
- Vector3f initAccVec = _ins.get_accel();
- uint8_t counter = 0;
-
- while ((initAccVec.length() < 9.0f || initAccVec.length() > 11) && counter++ < 20) {
- _ins.wait_for_sample();
- _ins.update();
- initAccVec = _ins.get_accel();
- }
-
- if (initAccVec.length() > 5.0f) {
-
- pitch = atan2f(initAccVec.x, norm(initAccVec.y, initAccVec.z));
-
- roll = atan2f(-initAccVec.y, -initAccVec.z);
- } else {
-
- roll = 0.0f;
- pitch = 0.0f;
- }
- _dcm_matrix.from_euler(roll, pitch, 0);
- }
- if (_last_startup_ms == 0) {
- load_watchdog_home();
- }
- _last_startup_ms = AP_HAL::millis();
- }
- void AP_AHRS_DCM::reset_attitude(const float &_roll, const float &_pitch, const float &_yaw)
- {
- _dcm_matrix.from_euler(_roll, _pitch, _yaw);
- }
- void
- AP_AHRS_DCM::check_matrix(void)
- {
- if (_dcm_matrix.is_nan()) {
-
- AP_AHRS_DCM::reset(true);
- return;
- }
-
-
-
-
- if (!(_dcm_matrix.c.x < 1.0f &&
- _dcm_matrix.c.x > -1.0f)) {
-
- normalize();
- if (_dcm_matrix.is_nan() ||
- fabsf(_dcm_matrix.c.x) > 10) {
-
-
-
-
- AP_AHRS_DCM::reset(true);
- }
- }
- }
- bool
- AP_AHRS_DCM::renorm(Vector3f const &a, Vector3f &result)
- {
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- const float renorm_val = 1.0f / a.length();
-
- _renorm_val_sum += renorm_val;
- _renorm_val_count++;
- if (!(renorm_val < 2.0f && renorm_val > 0.5f)) {
-
- if (!(renorm_val < 1.0e6f && renorm_val > 1.0e-6f)) {
-
-
-
-
-
-
- return false;
- }
- }
- result = a * renorm_val;
- return true;
- }
- void
- AP_AHRS_DCM::normalize(void)
- {
- const float error = _dcm_matrix.a * _dcm_matrix.b;
- const Vector3f t0 = _dcm_matrix.a - (_dcm_matrix.b * (0.5f * error));
- const Vector3f t1 = _dcm_matrix.b - (_dcm_matrix.a * (0.5f * error));
- const Vector3f t2 = t0 % t1;
- if (!renorm(t0, _dcm_matrix.a) ||
- !renorm(t1, _dcm_matrix.b) ||
- !renorm(t2, _dcm_matrix.c)) {
-
-
- _last_failure_ms = AP_HAL::millis();
- AP_AHRS_DCM::reset(true);
- }
- }
- float
- AP_AHRS_DCM::yaw_error_compass(void)
- {
- const Vector3f &mag = _compass->get_field();
-
- Vector2f rb = _dcm_matrix.mulXY(mag);
- if (rb.length() < FLT_EPSILON) {
- return 0.0f;
- }
- rb.normalize();
- if (rb.is_inf()) {
-
- return 0.0f;
- }
-
- if( !is_equal(_last_declination,_compass->get_declination()) ) {
- _last_declination = _compass->get_declination();
- _mag_earth.x = cosf(_last_declination);
- _mag_earth.y = sinf(_last_declination);
- }
-
-
- return rb % _mag_earth;
- }
- float
- AP_AHRS_DCM::_P_gain(float spin_rate)
- {
- if (spin_rate < ToRad(50)) {
- return 1.0f;
- }
- if (spin_rate > ToRad(500)) {
- return 10.0f;
- }
- return spin_rate/ToRad(50);
- }
- float
- AP_AHRS_DCM::_yaw_gain(void) const
- {
- const float VdotEFmag = norm(_accel_ef[_active_accel_instance].x,
- _accel_ef[_active_accel_instance].y);
- if (VdotEFmag <= 4.0f) {
- return 0.2f*(4.5f - VdotEFmag);
- }
- return 0.1f;
- }
- bool AP_AHRS_DCM::have_gps(void) const
- {
- if (AP::gps().status() <= AP_GPS::NO_FIX || !_gps_use) {
- return false;
- }
- return true;
- }
- bool AP_AHRS_DCM::use_fast_gains(void) const
- {
- return !hal.util->get_soft_armed() && (AP_HAL::millis() - _last_startup_ms) < 20000U;
- }
- bool AP_AHRS_DCM::use_compass(void)
- {
- if (!_compass || !_compass->use_for_yaw()) {
-
- return false;
- }
- if (!_flags.fly_forward || !have_gps()) {
-
- return true;
- }
- if (AP::gps().ground_speed() < GPS_SPEED_MIN) {
-
- return true;
- }
-
-
-
-
- const int32_t error = labs(wrap_180_cd(yaw_sensor - AP::gps().ground_course_cd()));
- if (error > 4500 && _wind.length() < AP::gps().ground_speed()*0.8f) {
- if (AP_HAL::millis() - _last_consistent_heading > 2000) {
-
-
- return false;
- }
- } else {
- _last_consistent_heading = AP_HAL::millis();
- }
-
- return true;
- }
- void
- AP_AHRS_DCM::drift_correction_yaw(void)
- {
- bool new_value = false;
- float yaw_error;
- float yaw_deltat;
- const AP_GPS &_gps = AP::gps();
- if (_compass && _compass->is_calibrating()) {
-
- return;
- }
-
- if (AP_AHRS_DCM::use_compass()) {
-
- if (_compass->last_update_usec() != _compass_last_update) {
- yaw_deltat = (_compass->last_update_usec() - _compass_last_update) * 1.0e-6f;
- _compass_last_update = _compass->last_update_usec();
-
-
-
- if (!_flags.have_initial_yaw && _compass->read()) {
- const float heading = _compass->calculate_heading(_dcm_matrix);
- _dcm_matrix.from_euler(roll, pitch, heading);
- _omega_yaw_P.zero();
- _flags.have_initial_yaw = true;
- }
- new_value = true;
- yaw_error = yaw_error_compass();
-
-
-
- _gps_last_update = _gps.last_fix_time_ms();
- }
- } else if (_flags.fly_forward && have_gps()) {
-
- if (_gps.last_fix_time_ms() != _gps_last_update &&
- _gps.ground_speed() >= GPS_SPEED_MIN) {
- yaw_deltat = (_gps.last_fix_time_ms() - _gps_last_update) * 1.0e-3f;
- _gps_last_update = _gps.last_fix_time_ms();
- new_value = true;
- const float gps_course_rad = ToRad(_gps.ground_course_cd() * 0.01f);
- const float yaw_error_rad = wrap_PI(gps_course_rad - yaw);
- yaw_error = sinf(yaw_error_rad);
-
- if (!_flags.have_initial_yaw ||
- yaw_deltat > 20 ||
- (_gps.ground_speed() >= 3*GPS_SPEED_MIN && fabsf(yaw_error_rad) >= 1.047f)) {
-
- _dcm_matrix.from_euler(roll, pitch, gps_course_rad);
- _omega_yaw_P.zero();
- _flags.have_initial_yaw = true;
- yaw_error = 0;
- }
- }
- }
- if (!new_value) {
-
-
-
- _omega_yaw_P *= 0.97f;
- return;
- }
-
- const float error_z = _dcm_matrix.c.z * yaw_error;
-
-
- const float spin_rate = _omega.length();
-
- if (_kp_yaw < AP_AHRS_YAW_P_MIN) {
- _kp_yaw = AP_AHRS_YAW_P_MIN;
- }
-
-
-
-
-
-
-
- _omega_yaw_P.z = error_z * _P_gain(spin_rate) * _kp_yaw * _yaw_gain();
- if (use_fast_gains()) {
- _omega_yaw_P.z *= 8;
- }
-
-
- if (yaw_deltat < 2.0f && spin_rate < ToRad(SPIN_RATE_LIMIT)) {
-
- _omega_I_sum.z += error_z * _ki_yaw * yaw_deltat;
- }
- _error_yaw = 0.8f * _error_yaw + 0.2f * fabsf(yaw_error);
- }
- Vector3f AP_AHRS_DCM::ra_delayed(uint8_t instance, const Vector3f &ra)
- {
-
- const Vector3f ret = _ra_delay_buffer[instance];
- _ra_delay_buffer[instance] = ra;
- if (ret.is_zero()) {
-
-
- return ra;
- }
- return ret;
- }
- void
- AP_AHRS_DCM::drift_correction(float deltat)
- {
- Vector3f velocity;
- uint32_t last_correction_time;
-
-
- drift_correction_yaw();
- const AP_InertialSensor &_ins = AP::ins();
-
- uint8_t healthy_count = 0;
- for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
- if (_ins.use_accel(i) && healthy_count < 2) {
-
- Vector3f delta_velocity;
- _ins.get_delta_velocity(i, delta_velocity);
- const float delta_velocity_dt = _ins.get_delta_velocity_dt(i);
- if (delta_velocity_dt > 0) {
- _accel_ef[i] = _dcm_matrix * (delta_velocity / delta_velocity_dt);
-
- _ra_sum[i] += _accel_ef[i] * deltat;
- }
- healthy_count++;
- }
- }
-
- if (_ins.get_accel_count() == 2 && _ins.use_accel(0) && _ins.use_accel(1)) {
- const float imu1_weight_target = _active_accel_instance == 0 ? 1.0f : 0.0f;
-
- _imu1_weight += constrain_float(imu1_weight_target-_imu1_weight, -deltat, deltat);
- _accel_ef_blended = _accel_ef[0] * _imu1_weight + _accel_ef[1] * (1.0f - _imu1_weight);
- } else {
- _accel_ef_blended = _accel_ef[_ins.get_primary_accel()];
- }
-
-
- _ra_deltat += deltat;
- const AP_GPS &_gps = AP::gps();
- if (!have_gps() ||
- _gps.status() < AP_GPS::GPS_OK_FIX_3D ||
- _gps.num_sats() < _gps_minsats) {
-
-
-
-
-
-
-
- if (_ra_deltat < 0.2f) {
-
- return;
- }
- float airspeed;
- if (airspeed_sensor_enabled()) {
- airspeed = _airspeed->get_airspeed();
- } else {
- airspeed = _last_airspeed;
- }
-
-
- velocity = _dcm_matrix.colx() * airspeed;
-
- velocity += _wind;
- last_correction_time = AP_HAL::millis();
- _have_gps_lock = false;
- } else {
- if (_gps.last_fix_time_ms() == _ra_sum_start) {
-
- return;
- }
- velocity = _gps.velocity();
- last_correction_time = _gps.last_fix_time_ms();
- if (_have_gps_lock == false) {
-
-
- _last_velocity = velocity;
- }
- _have_gps_lock = true;
-
- Vector3f airspeed = velocity - _wind;
-
- const Matrix3f &rot = get_rotation_body_to_ned();
- airspeed = rot.mul_transpose(airspeed);
-
-
- _last_airspeed = MAX(airspeed.x, 0);
- }
- if (have_gps()) {
-
- _last_lat = _gps.location().lat;
- _last_lng = _gps.location().lng;
- _position_offset_north = 0;
- _position_offset_east = 0;
-
-
- _have_position = true;
- } else {
-
- _position_offset_north += velocity.x * _ra_deltat;
- _position_offset_east += velocity.y * _ra_deltat;
- }
-
-
- if (_ra_sum_start == 0) {
- _ra_sum_start = last_correction_time;
- _last_velocity = velocity;
- return;
- }
-
-
- Vector3f GA_e(0.0f, 0.0f, -1.0f);
- if (_ra_deltat <= 0) {
-
- return;
- }
-
- bool using_gps_corrections = false;
- float ra_scale = 1.0f/(_ra_deltat*GRAVITY_MSS);
- if (_flags.correct_centrifugal && (_have_gps_lock || _flags.fly_forward)) {
- const float v_scale = gps_gain.get() * ra_scale;
- const Vector3f vdelta = (velocity - _last_velocity) * v_scale;
- GA_e += vdelta;
- GA_e.normalize();
- if (GA_e.is_inf()) {
-
- _last_failure_ms = AP_HAL::millis();
- return;
- }
- using_gps_corrections = true;
- }
-
-
-
-
-
-
-
-
-
- Vector3f error[INS_MAX_INSTANCES];
- float error_dirn[INS_MAX_INSTANCES];
- Vector3f GA_b[INS_MAX_INSTANCES];
- int8_t besti = -1;
- float best_error = 0;
- for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
- if (!_ins.get_accel_health(i)) {
-
- continue;
- }
- _ra_sum[i] *= ra_scale;
-
- if (using_gps_corrections) {
- GA_b[i] = ra_delayed(i, _ra_sum[i]);
- } else {
- GA_b[i] = _ra_sum[i];
- }
- if (GA_b[i].is_zero()) {
-
- continue;
- }
- GA_b[i].normalize();
- if (GA_b[i].is_inf()) {
-
- continue;
- }
- error[i] = GA_b[i] % GA_e;
-
- error_dirn[i] = GA_b[i] * GA_e;
- const float error_length = error[i].length();
- if (besti == -1 || error_length < best_error) {
- besti = i;
- best_error = error_length;
- }
-
- if (error_dirn[besti] < 0.0f) {
- best_error = 1.0f;
- }
- }
- if (besti == -1) {
-
- _last_failure_ms = AP_HAL::millis();
- return;
- }
- _active_accel_instance = besti;
- #define YAW_INDEPENDENT_DRIFT_CORRECTION 0
- #if YAW_INDEPENDENT_DRIFT_CORRECTION
-
- const float earth_error_Z = error.z;
-
- const float tilt = norm(GA_e.x, GA_e.y);
-
- const float theta = atan2f(GA_b[besti].y, GA_b[besti].x);
-
- const Vector3f GA_e2 = Vector3f(cosf(theta)*tilt, sinf(theta)*tilt, GA_e.z);
-
- error = GA_b[besti] % GA_e2;
- error.z = earth_error_Z;
- #endif
-
-
-
-
- if (AP_AHRS_DCM::use_compass()) {
- if (have_gps() && is_equal(gps_gain.get(), 1.0f)) {
- error[besti].z *= sinf(fabsf(roll));
- } else {
- error[besti].z = 0;
- }
- }
-
-
-
- if (!_ins.healthy()) {
- error[besti].zero();
- } else {
-
- error[besti] = _dcm_matrix.mul_transpose(error[besti]);
- }
- if (error[besti].is_nan() || error[besti].is_inf()) {
-
- check_matrix();
- _last_failure_ms = AP_HAL::millis();
- return;
- }
- _error_rp = 0.8f * _error_rp + 0.2f * best_error;
-
- const float spin_rate = _omega.length();
-
- if (_kp < AP_AHRS_RP_P_MIN) {
- _kp = AP_AHRS_RP_P_MIN;
- }
-
-
-
- _omega_P = error[besti] * _P_gain(spin_rate) * _kp;
- if (use_fast_gains()) {
- _omega_P *= 8;
- }
- if (_flags.fly_forward && _gps.status() >= AP_GPS::GPS_OK_FIX_2D &&
- _gps.ground_speed() < GPS_SPEED_MIN &&
- _ins.get_accel().x >= 7 &&
- pitch_sensor > -3000 && pitch_sensor < 3000) {
-
-
-
- _omega_P *= 0.5f;
- }
-
- if (spin_rate < ToRad(SPIN_RATE_LIMIT)) {
- _omega_I_sum += error[besti] * _ki * _ra_deltat;
- _omega_I_sum_time += _ra_deltat;
- }
- if (_omega_I_sum_time >= 5) {
-
-
-
-
- const float change_limit = _gyro_drift_limit * _omega_I_sum_time;
- _omega_I_sum.x = constrain_float(_omega_I_sum.x, -change_limit, change_limit);
- _omega_I_sum.y = constrain_float(_omega_I_sum.y, -change_limit, change_limit);
- _omega_I_sum.z = constrain_float(_omega_I_sum.z, -change_limit, change_limit);
- _omega_I += _omega_I_sum;
- _omega_I_sum.zero();
- _omega_I_sum_time = 0;
- }
-
- memset((void *)&_ra_sum[0], 0, sizeof(_ra_sum));
- _ra_deltat = 0;
- _ra_sum_start = last_correction_time;
-
- _last_velocity = velocity;
- }
- void AP_AHRS_DCM::estimate_wind(void)
- {
- if (!_flags.wind_estimation) {
- return;
- }
- const Vector3f &velocity = _last_velocity;
-
-
-
- const Vector3f fuselageDirection = _dcm_matrix.colx();
- const Vector3f fuselageDirectionDiff = fuselageDirection - _last_fuse;
- const uint32_t now = AP_HAL::millis();
-
- if (now - _last_wind_time > 10000) {
- _last_wind_time = now;
- _last_fuse = fuselageDirection;
- _last_vel = velocity;
- return;
- }
- float diff_length = fuselageDirectionDiff.length();
- if (diff_length > 0.2f) {
-
-
- float V;
- const Vector3f velocityDiff = velocity - _last_vel;
-
- V = velocityDiff.length() / diff_length;
- const Vector3f fuselageDirectionSum = fuselageDirection + _last_fuse;
- const Vector3f velocitySum = velocity + _last_vel;
- _last_fuse = fuselageDirection;
- _last_vel = velocity;
- const float theta = atan2f(velocityDiff.y, velocityDiff.x) - atan2f(fuselageDirectionDiff.y, fuselageDirectionDiff.x);
- const float sintheta = sinf(theta);
- const float costheta = cosf(theta);
- Vector3f wind = Vector3f();
- wind.x = velocitySum.x - V * (costheta * fuselageDirectionSum.x - sintheta * fuselageDirectionSum.y);
- wind.y = velocitySum.y - V * (sintheta * fuselageDirectionSum.x + costheta * fuselageDirectionSum.y);
- wind.z = velocitySum.z - V * fuselageDirectionSum.z;
- wind *= 0.5f;
- if (wind.length() < _wind.length() + 20) {
- _wind = _wind * 0.95f + wind * 0.05f;
- }
- _last_wind_time = now;
- } else if (now - _last_wind_time > 2000 && airspeed_sensor_enabled()) {
-
- const Vector3f airspeed = _dcm_matrix.colx() * _airspeed->get_airspeed();
- const Vector3f wind = velocity - (airspeed * get_EAS2TAS());
- _wind = _wind * 0.92f + wind * 0.08f;
- }
- }
- void
- AP_AHRS_DCM::euler_angles(void)
- {
- _body_dcm_matrix = _dcm_matrix * get_rotation_vehicle_body_to_autopilot_body();
- _body_dcm_matrix.to_euler(&roll, &pitch, &yaw);
- update_cd_values();
- }
- bool AP_AHRS_DCM::get_position(struct Location &loc) const
- {
- loc.lat = _last_lat;
- loc.lng = _last_lng;
- loc.alt = AP::baro().get_altitude() * 100 + _home.alt;
- loc.relative_alt = 0;
- loc.terrain_alt = 0;
- loc.offset(_position_offset_north, _position_offset_east);
- const AP_GPS &_gps = AP::gps();
- if (_flags.fly_forward && _have_position) {
- float gps_delay_sec = 0;
- _gps.get_lag(gps_delay_sec);
- loc.offset_bearing(_gps.ground_course_cd() * 0.01f, _gps.ground_speed() * gps_delay_sec);
- }
- return _have_position;
- }
- bool AP_AHRS_DCM::airspeed_estimate(float *airspeed_ret) const
- {
- bool ret = false;
- if (airspeed_sensor_enabled()) {
- *airspeed_ret = _airspeed->get_airspeed();
- return true;
- }
- if (!_flags.wind_estimation) {
- return false;
- }
-
- if (have_gps()) {
- *airspeed_ret = _last_airspeed;
- ret = true;
- }
- if (ret && _wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
-
-
- const float gnd_speed = AP::gps().ground_speed();
- float true_airspeed = *airspeed_ret * get_EAS2TAS();
- true_airspeed = constrain_float(true_airspeed,
- gnd_speed - _wind_max,
- gnd_speed + _wind_max);
- *airspeed_ret = true_airspeed / get_EAS2TAS();
- }
- if (!ret) {
-
-
- *airspeed_ret = _last_airspeed;
- }
- return ret;
- }
- bool AP_AHRS_DCM::set_home(const Location &loc)
- {
-
- if (loc.lat == 0 && loc.lng == 0 && loc.alt == 0) {
- return false;
- }
- if (!loc.check_latlng()) {
- return false;
- }
-
-
-
- Location tmp = loc;
- if (!tmp.change_alt_frame(Location::AltFrame::ABSOLUTE)) {
- return false;
- }
- _home = tmp;
- _home_is_set = true;
- Log_Write_Home_And_Origin();
-
- gcs().send_message(MSG_HOME);
- gcs().send_message(MSG_ORIGIN);
- AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
- pd.home_lat = loc.lat;
- pd.home_lon = loc.lng;
- pd.home_alt_cm = loc.alt;
- return true;
- }
- void AP_AHRS_DCM::get_relative_position_D_home(float &posD) const
- {
- posD = -AP::baro().get_altitude();
- }
- bool AP_AHRS_DCM::healthy(void) const
- {
-
- return (_last_failure_ms == 0 || AP_HAL::millis() - _last_failure_ms > 5000);
- }
- bool AP_AHRS_DCM::get_velocity_NED(Vector3f &vec) const
- {
- const AP_GPS &_gps = AP::gps();
- if (_gps.status() < AP_GPS::GPS_OK_FIX_3D) {
- return false;
- }
- vec = _gps.velocity();
- return true;
- }
|