Path: blob/master/libraries/AP_AHRS/AP_AHRS_Backend.cpp
9492 views
/*1APM_AHRS.cpp23This program is free software: you can redistribute it and/or modify4it under the terms of the GNU General Public License as published by5the Free Software Foundation, either version 3 of the License, or6(at your option) any later version.78This program is distributed in the hope that it will be useful,9but WITHOUT ANY WARRANTY; without even the implied warranty of10MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the11GNU General Public License for more details.1213You should have received a copy of the GNU General Public License14along with this program. If not, see <http://www.gnu.org/licenses/>.15*/16#include "AP_AHRS.h"17#include "AP_AHRS_View.h"1819#include <AP_Common/Location.h>20#include <AP_HAL/AP_HAL.h>21#include <AP_Logger/AP_Logger.h>22#include <AP_GPS/AP_GPS.h>23#include <AP_Baro/AP_Baro.h>24#include <AP_Compass/AP_Compass.h>25#include <AP_Vehicle/AP_Vehicle_Type.h>2627extern const AP_HAL::HAL& hal;2829void AP_AHRS_Backend::init()30{31}3233// return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)34Vector3f AP_AHRS::get_gyro_latest(void) const35{36const uint8_t primary_gyro = get_primary_gyro_index();37return AP::ins().get_gyro(primary_gyro) + get_gyro_drift();38}3940// set_trim41void AP_AHRS::set_trim(const Vector3f &new_trim)42{43const Vector3f trim {44constrain_float(new_trim.x, radians(-AP_AHRS_TRIM_LIMIT), radians(AP_AHRS_TRIM_LIMIT)),45constrain_float(new_trim.y, radians(-AP_AHRS_TRIM_LIMIT), radians(AP_AHRS_TRIM_LIMIT)),46constrain_float(new_trim.z, radians(-AP_AHRS_TRIM_LIMIT), radians(AP_AHRS_TRIM_LIMIT))47};48_trim.set_and_save(trim);49}5051// add_trim - adjust the roll and pitch trim up to a total of 10 degrees52void AP_AHRS::add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom)53{54Vector3f trim = _trim.get();5556// add new trim57trim.x = constrain_float(trim.x + roll_in_radians, radians(-AP_AHRS_TRIM_LIMIT), radians(AP_AHRS_TRIM_LIMIT));58trim.y = constrain_float(trim.y + pitch_in_radians, radians(-AP_AHRS_TRIM_LIMIT), radians(AP_AHRS_TRIM_LIMIT));5960// set new trim values61_trim.set(trim);6263// save to eeprom64if( save_to_eeprom ) {65_trim.save();66}67}6869// Set the board mounting orientation from AHRS_ORIENTATION parameter70void AP_AHRS::update_orientation()71{72const uint32_t now_ms = AP_HAL::millis();73if (last_orientation_update_ms != 0 &&74now_ms - last_orientation_update_ms < 1000) {75// only update once/second76return;77}7879// never update while armed - unless we've never updated80// (e.g. mid-air reboot or ARMING_REQUIRED=NO on Plane):81if (hal.util->get_soft_armed() && last_orientation_update_ms != 0) {82return;83}8485last_orientation_update_ms = now_ms;8687const enum Rotation orientation = (enum Rotation)_board_orientation.get();8889AP::ins().set_board_orientation(orientation);90AP::compass().set_board_orientation(orientation);91}9293/*94calculate sin and cos of roll/pitch/yaw from a body_to_ned rotation matrix95*/96void AP_AHRS::calc_trig(const Matrix3f &rot,97float &cr, float &cp, float &cy,98float &sr, float &sp, float &sy) const99{100Vector2f yaw_vector(rot.a.x, rot.b.x);101102if (fabsf(yaw_vector.x) > 0 ||103fabsf(yaw_vector.y) > 0) {104yaw_vector.normalize();105}106sy = constrain_float(yaw_vector.y, -1.0f, 1.0f);107cy = constrain_float(yaw_vector.x, -1.0f, 1.0f);108109// sanity checks110if (yaw_vector.is_inf() || yaw_vector.is_nan()) {111sy = 0.0f;112cy = 1.0f;113}114115const float cx2 = rot.c.x * rot.c.x;116if (cx2 >= 1.0f) {117cp = 0;118cr = 1.0f;119} else {120cp = safe_sqrt(1 - cx2);121cr = rot.c.z / cp;122}123cp = constrain_float(cp, 0.0f, 1.0f);124cr = constrain_float(cr, -1.0f, 1.0f); // this relies on constrain_float() of infinity doing the right thing125126sp = -rot.c.x;127128if (!is_zero(cp)) {129sr = rot.c.y / cp;130}131132if (is_zero(cp) || isinf(cr) || isnan(cr) || isinf(sr) || isnan(sr)) {133float r, p, y;134rot.to_euler(&r, &p, &y);135cr = cosf(r);136sr = sinf(r);137}138}139140// update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude141// should be called after _dcm_matrix is updated142void AP_AHRS::update_trig(void)143{144calc_trig(get_rotation_body_to_ned(),145_cos_roll, _cos_pitch, _cos_yaw,146_sin_roll, _sin_pitch, _sin_yaw);147}148149/*150update the centi-degree values151*/152void AP_AHRS::update_cd_values(void)153{154roll_sensor = degrees(roll) * 100;155pitch_sensor = degrees(pitch) * 100;156yaw_sensor = degrees(yaw) * 100;157if (yaw_sensor < 0)158yaw_sensor += 36000;159160rpy_deg[0] = degrees(roll);161rpy_deg[1] = degrees(pitch);162rpy_deg[2] = wrap_360(degrees(yaw)); // we are probably already in trouble if this is required163}164165/*166create a rotated view of AP_AHRS with optional pitch trim167*/168AP_AHRS_View *AP_AHRS::create_view(enum Rotation rotation, float pitch_trim_deg)169{170if (_view != nullptr) {171// can only have one172return nullptr;173}174_view = NEW_NOTHROW AP_AHRS_View(*this, rotation, pitch_trim_deg);175return _view;176}177178/*179* Update AOA and SSA estimation based on airspeed, velocity vector and wind vector180*181* Based on:182* "On estimation of wind velocity, angle-of-attack and sideslip angle of small UAVs using standard sensors" by183* Tor A. Johansen, Andrea Cristofaro, Kim Sorensen, Jakob M. Hansen, Thor I. Fossen184*185* "Multi-Stage Fusion Algorithm for Estimation of Aerodynamic Angles in Mini Aerial Vehicle" by186* C.Ramprasadh and Hemendra Arya187*188* "ANGLE OF ATTACK AND SIDESLIP ESTIMATION USING AN INERTIAL REFERENCE PLATFORM" by189* JOSEPH E. ZEIS, JR., CAPTAIN, USAF190*/191void AP_AHRS::update_AOA_SSA(void)192{193#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)194const uint32_t now = AP_HAL::millis();195if (now - _last_AOA_update_ms < 50) {196// don't update at more than 20Hz197return;198}199_last_AOA_update_ms = now;200201Vector3f aoa_velocity, aoa_wind;202203// get velocity and wind204if (get_velocity_NED(aoa_velocity) == false) {205return;206}207208aoa_wind = wind_estimate();209210// Rotate vectors to the body frame and calculate velocity and wind211const Matrix3f &rot = get_rotation_body_to_ned();212aoa_velocity = rot.mul_transpose(aoa_velocity);213aoa_wind = rot.mul_transpose(aoa_wind);214215// calculate relative velocity in body coordinates216aoa_velocity = aoa_velocity - aoa_wind;217const float vel_len = aoa_velocity.length();218219// do not calculate if speed is too low220if (vel_len < 2.0) {221_AOA = 0;222_SSA = 0;223return;224}225226// Calculate AOA and SSA227if (aoa_velocity.x > 0) {228_AOA = degrees(atanf(aoa_velocity.z / aoa_velocity.x));229} else {230_AOA = 0;231}232233_SSA = degrees(safe_asin(aoa_velocity.y / vel_len));234#endif235}236237// rotate a 2D vector from earth frame to body frame238Vector2f AP_AHRS::earth_to_body2D(const Vector2f &ef) const239{240return Vector2f(ef.x * _cos_yaw + ef.y * _sin_yaw,241-ef.x * _sin_yaw + ef.y * _cos_yaw);242}243244// rotate a 2D vector from earth frame to body frame245Vector2f AP_AHRS::body_to_earth2D(const Vector2f &bf) const246{247return Vector2f(bf.x * _cos_yaw - bf.y * _sin_yaw,248bf.x * _sin_yaw + bf.y * _cos_yaw);249}250251// rotate a 2D vector from earth frame to body frame252Vector2p AP_AHRS::body_to_earth2D_p(const Vector2p &bf) const253{254return Vector2p(bf.x * _cos_yaw - bf.y * _sin_yaw,255bf.x * _sin_yaw + bf.y * _cos_yaw);256}257258#if HAL_LOGGING_ENABLED259// log ahrs home and EKF origin260void AP_AHRS::Log_Write_Home_And_Origin()261{262AP_Logger *logger = AP_Logger::get_singleton();263if (logger == nullptr) {264return;265}266Location ekf_orig;267if (get_origin(ekf_orig)) {268Write_Origin(LogOriginType::ekf_origin, ekf_orig);269}270271if (_home_is_set) {272Write_Origin(LogOriginType::ahrs_home, _home);273}274}275#endif276277// get apparent to true airspeed ratio278float AP_AHRS_Backend::get_EAS2TAS(void) {279return AP::baro()._get_EAS2TAS();280}281282// return current vibration vector for primary IMU283Vector3f AP_AHRS::get_vibration(void) const284{285return AP::ins().get_vibration_levels();286}287288void AP_AHRS::set_takeoff_expected(bool b)289{290takeoff_expected = b;291takeoff_expected_start_ms = AP_HAL::millis();292}293294void AP_AHRS::set_touchdown_expected(bool b)295{296touchdown_expected = b;297touchdown_expected_start_ms = AP_HAL::millis();298}299300/*301update takeoff/touchdown flags302*/303void AP_AHRS::update_flags(void)304{305const uint32_t timeout_ms = 1000;306if (takeoff_expected && AP_HAL::millis() - takeoff_expected_start_ms > timeout_ms) {307takeoff_expected = false;308}309if (touchdown_expected && AP_HAL::millis() - touchdown_expected_start_ms > timeout_ms) {310touchdown_expected = false;311}312}313314315