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_View.h
Views: 1798
#pragma once12/*3This 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*/1617/*18* AHRS View class - for creating a 2nd view of the vehicle attitude19*20*/2122#include "AP_AHRS.h"2324// fwd declarations to avoid include errors25class AC_AttitudeControl;26class AC_PosControl;2728class AP_AHRS_View29{30public:31// Constructor32AP_AHRS_View(AP_AHRS &ahrs, enum Rotation rotation, float pitch_trim_deg=0);3334// update state35void update();3637// empty virtual destructor38virtual ~AP_AHRS_View() {}3940// return a smoothed and corrected gyro vector41const Vector3f &get_gyro(void) const {42return gyro;43}4445// return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)46Vector3f get_gyro_latest(void) const;4748// return a DCM rotation matrix representing our current attitude in this view49const Matrix3f &get_rotation_body_to_ned(void) const {50return rot_body_to_ned;51}5253// return a Quaternion representing our current attitude in this view54void get_quat_body_to_ned(Quaternion &quat) const {55quat.from_rotation_matrix(rot_body_to_ned);56}5758// apply pitch trim59void set_pitch_trim(float trim_deg);6061// helper trig value accessors62float cos_roll() const {63return trig.cos_roll;64}65float cos_pitch() const {66return trig.cos_pitch;67}68float cos_yaw() const {69return trig.cos_yaw;70}71float sin_roll() const {72return trig.sin_roll;73}74float sin_pitch() const {75return trig.sin_pitch;76}77float sin_yaw() const {78return trig.sin_yaw;79}808182/*83wrappers around ahrs functions which pass-thru directly. See84AP_AHRS.h for description of each function85*/86bool get_location(Location &loc) const WARN_IF_UNUSED {87return ahrs.get_location(loc);88}8990bool wind_estimate(Vector3f &wind) {91return ahrs.wind_estimate(wind);92}9394bool airspeed_estimate(float &airspeed_ret) const WARN_IF_UNUSED {95return ahrs.airspeed_estimate(airspeed_ret);96}9798bool airspeed_estimate_true(float &airspeed_ret) const WARN_IF_UNUSED {99return ahrs.airspeed_estimate_true(airspeed_ret);100}101102float get_EAS2TAS(void) const {103return ahrs.get_EAS2TAS();104}105106Vector2f groundspeed_vector(void) {107return ahrs.groundspeed_vector();108}109110bool get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED {111return ahrs.get_velocity_NED(vec);112}113114bool get_relative_position_NED_home(Vector3f &vec) const WARN_IF_UNUSED {115return ahrs.get_relative_position_NED_home(vec);116}117118bool get_relative_position_NED_origin(Vector3f &vec) const WARN_IF_UNUSED {119return ahrs.get_relative_position_NED_origin(vec);120}121122bool get_relative_position_NE_home(Vector2f &vecNE) const WARN_IF_UNUSED {123return ahrs.get_relative_position_NE_home(vecNE);124}125126bool get_relative_position_NE_origin(Vector2f &vecNE) const WARN_IF_UNUSED {127return ahrs.get_relative_position_NE_origin(vecNE);128}129130void get_relative_position_D_home(float &posD) const {131ahrs.get_relative_position_D_home(posD);132}133134bool get_relative_position_D_origin(float &posD) const WARN_IF_UNUSED {135return ahrs.get_relative_position_D_origin(posD);136}137138float groundspeed(void) {139return ahrs.groundspeed();140}141142const Vector3f &get_accel_ef(void) const {143return ahrs.get_accel_ef();144}145146uint32_t getLastPosNorthEastReset(Vector2f &pos) WARN_IF_UNUSED {147return ahrs.getLastPosNorthEastReset(pos);148}149150uint32_t getLastPosDownReset(float &posDelta) WARN_IF_UNUSED {151return ahrs.getLastPosDownReset(posDelta);152}153154// rotate a 2D vector from earth frame to body frame155// in result, x is forward, y is right156Vector2f earth_to_body2D(const Vector2f &ef_vector) const;157158// rotate a 2D vector from earth frame to body frame159// in input, x is forward, y is right160Vector2f body_to_earth2D(const Vector2f &bf) const;161162// return the average size of the roll/pitch error estimate163// since last call164float get_error_rp(void) const {165return ahrs.get_error_rp();166}167168// return the average size of the yaw error estimate169// since last call170float get_error_yaw(void) const {171return ahrs.get_error_yaw();172}173174// Logging Functions175void Write_AttitudeView(const Vector3f &targets) const;176177float roll;178float pitch;179float yaw;180int32_t roll_sensor;181int32_t pitch_sensor;182int32_t yaw_sensor;183184185// get current rotation186// note that this may not be the rotation were actually using, see _pitch_trim_deg187enum Rotation get_rotation(void) const {188return rotation;189}190191// get pitch trim (deg)192float get_pitch_trim() const { return _pitch_trim_deg; }193194// Rotate vector from AHRS reference frame to AHRS view refences frame195void rotate(Vector3f &vec) const;196197private:198const enum Rotation rotation;199AP_AHRS &ahrs;200201// body frame rotation for this View202Matrix3f rot_view;203// transpose of rot_view204Matrix3f rot_view_T;205Matrix3f rot_body_to_ned;206Vector3f gyro;207208struct {209float cos_roll;210float cos_pitch;211float cos_yaw;212float sin_roll;213float sin_pitch;214float sin_yaw;215} trig;216217float y_angle;218float _pitch_trim_deg;219};220221222