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_Backend.cpp
Views: 1798
/*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, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT)),45constrain_float(new_trim.y, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT)),46constrain_float(new_trim.z, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(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, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT));58trim.y = constrain_float(trim.y + pitch_in_radians, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(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 (now_ms - last_orientation_update_ms < 1000) {74// only update once/second75return;76}7778// never update while armed - unless we've never updated79// (e.g. mid-air reboot or ARMING_REQUIRED=NO on Plane):80if (hal.util->get_soft_armed() && last_orientation_update_ms != 0) {81return;82}8384last_orientation_update_ms = now_ms;8586const enum Rotation orientation = (enum Rotation)_board_orientation.get();8788AP::ins().set_board_orientation(orientation);89AP::compass().set_board_orientation(orientation);90}9192/*93calculate sin and cos of roll/pitch/yaw from a body_to_ned rotation matrix94*/95void AP_AHRS::calc_trig(const Matrix3f &rot,96float &cr, float &cp, float &cy,97float &sr, float &sp, float &sy) const98{99Vector2f yaw_vector(rot.a.x, rot.b.x);100101if (fabsf(yaw_vector.x) > 0 ||102fabsf(yaw_vector.y) > 0) {103yaw_vector.normalize();104}105sy = constrain_float(yaw_vector.y, -1.0f, 1.0f);106cy = constrain_float(yaw_vector.x, -1.0f, 1.0f);107108// sanity checks109if (yaw_vector.is_inf() || yaw_vector.is_nan()) {110sy = 0.0f;111cy = 1.0f;112}113114const float cx2 = rot.c.x * rot.c.x;115if (cx2 >= 1.0f) {116cp = 0;117cr = 1.0f;118} else {119cp = safe_sqrt(1 - cx2);120cr = rot.c.z / cp;121}122cp = constrain_float(cp, 0.0f, 1.0f);123cr = constrain_float(cr, -1.0f, 1.0f); // this relies on constrain_float() of infinity doing the right thing124125sp = -rot.c.x;126127if (!is_zero(cp)) {128sr = rot.c.y / cp;129}130131if (is_zero(cp) || isinf(cr) || isnan(cr) || isinf(sr) || isnan(sr)) {132float r, p, y;133rot.to_euler(&r, &p, &y);134cr = cosf(r);135sr = sinf(r);136}137}138139// update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude140// should be called after _dcm_matrix is updated141void AP_AHRS::update_trig(void)142{143calc_trig(get_rotation_body_to_ned(),144_cos_roll, _cos_pitch, _cos_yaw,145_sin_roll, _sin_pitch, _sin_yaw);146}147148/*149update the centi-degree values150*/151void AP_AHRS::update_cd_values(void)152{153roll_sensor = degrees(roll) * 100;154pitch_sensor = degrees(pitch) * 100;155yaw_sensor = degrees(yaw) * 100;156if (yaw_sensor < 0)157yaw_sensor += 36000;158}159160/*161create a rotated view of AP_AHRS with optional pitch trim162*/163AP_AHRS_View *AP_AHRS::create_view(enum Rotation rotation, float pitch_trim_deg)164{165if (_view != nullptr) {166// can only have one167return nullptr;168}169_view = NEW_NOTHROW AP_AHRS_View(*this, rotation, pitch_trim_deg);170return _view;171}172173/*174* Update AOA and SSA estimation based on airspeed, velocity vector and wind vector175*176* Based on:177* "On estimation of wind velocity, angle-of-attack and sideslip angle of small UAVs using standard sensors" by178* Tor A. Johansen, Andrea Cristofaro, Kim Sorensen, Jakob M. Hansen, Thor I. Fossen179*180* "Multi-Stage Fusion Algorithm for Estimation of Aerodynamic Angles in Mini Aerial Vehicle" by181* C.Ramprasadh and Hemendra Arya182*183* "ANGLE OF ATTACK AND SIDESLIP ESTIMATION USING AN INERTIAL REFERENCE PLATFORM" by184* JOSEPH E. ZEIS, JR., CAPTAIN, USAF185*/186void AP_AHRS::update_AOA_SSA(void)187{188#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)189const uint32_t now = AP_HAL::millis();190if (now - _last_AOA_update_ms < 50) {191// don't update at more than 20Hz192return;193}194_last_AOA_update_ms = now;195196Vector3f aoa_velocity, aoa_wind;197198// get velocity and wind199if (get_velocity_NED(aoa_velocity) == false) {200return;201}202203aoa_wind = wind_estimate();204205// Rotate vectors to the body frame and calculate velocity and wind206const Matrix3f &rot = get_rotation_body_to_ned();207aoa_velocity = rot.mul_transpose(aoa_velocity);208aoa_wind = rot.mul_transpose(aoa_wind);209210// calculate relative velocity in body coordinates211aoa_velocity = aoa_velocity - aoa_wind;212const float vel_len = aoa_velocity.length();213214// do not calculate if speed is too low215if (vel_len < 2.0) {216_AOA = 0;217_SSA = 0;218return;219}220221// Calculate AOA and SSA222if (aoa_velocity.x > 0) {223_AOA = degrees(atanf(aoa_velocity.z / aoa_velocity.x));224} else {225_AOA = 0;226}227228_SSA = degrees(safe_asin(aoa_velocity.y / vel_len));229#endif230}231232// rotate a 2D vector from earth frame to body frame233Vector2f AP_AHRS::earth_to_body2D(const Vector2f &ef) const234{235return Vector2f(ef.x * _cos_yaw + ef.y * _sin_yaw,236-ef.x * _sin_yaw + ef.y * _cos_yaw);237}238239// rotate a 2D vector from earth frame to body frame240Vector2f AP_AHRS::body_to_earth2D(const Vector2f &bf) const241{242return Vector2f(bf.x * _cos_yaw - bf.y * _sin_yaw,243bf.x * _sin_yaw + bf.y * _cos_yaw);244}245246#if HAL_LOGGING_ENABLED247// log ahrs home and EKF origin248void AP_AHRS::Log_Write_Home_And_Origin()249{250AP_Logger *logger = AP_Logger::get_singleton();251if (logger == nullptr) {252return;253}254Location ekf_orig;255if (get_origin(ekf_orig)) {256Write_Origin(LogOriginType::ekf_origin, ekf_orig);257}258259if (_home_is_set) {260Write_Origin(LogOriginType::ahrs_home, _home);261}262}263#endif264265// get apparent to true airspeed ratio266float AP_AHRS_Backend::get_EAS2TAS(void) {267return AP::baro()._get_EAS2TAS();268}269270// return current vibration vector for primary IMU271Vector3f AP_AHRS::get_vibration(void) const272{273return AP::ins().get_vibration_levels();274}275276void AP_AHRS::set_takeoff_expected(bool b)277{278takeoff_expected = b;279takeoff_expected_start_ms = AP_HAL::millis();280}281282void AP_AHRS::set_touchdown_expected(bool b)283{284touchdown_expected = b;285touchdown_expected_start_ms = AP_HAL::millis();286}287288/*289update takeoff/touchdown flags290*/291void AP_AHRS::update_flags(void)292{293const uint32_t timeout_ms = 1000;294if (takeoff_expected && AP_HAL::millis() - takeoff_expected_start_ms > timeout_ms) {295takeoff_expected = false;296}297if (touchdown_expected && AP_HAL::millis() - touchdown_expected_start_ms > timeout_ms) {298touchdown_expected = false;299}300}301302303