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_External.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* External based AHRS (Attitude Heading Reference System) interface for19* ArduPilot20*21*/2223#include "AP_AHRS_config.h"2425#if AP_AHRS_EXTERNAL_ENABLED2627#include "AP_AHRS_Backend.h"2829class AP_AHRS_External : public AP_AHRS_Backend {30public:3132using AP_AHRS_Backend::AP_AHRS_Backend;3334/* Do not allow copies */35CLASS_NO_COPY(AP_AHRS_External);3637// reset the current gyro drift estimate38// should be called if gyro offsets are recalculated39void reset_gyro_drift() override {}4041// Methods42bool initialised() const override;43void update() override;44void get_results(Estimates &results) override;45void reset() override {}4647// return a wind estimation vector, in m/s48bool wind_estimate(Vector3f &ret) const override {49return false;50}5152// return a ground vector estimate in meters/second, in North/East order53Vector2f groundspeed_vector() override;5455bool use_compass() override {56// this is actually never called at the moment; we use dcm's57// return value.58return true;59}6061// return the quaternion defining the rotation from NED to XYZ (body) axes62bool get_quaternion(Quaternion &quat) const override WARN_IF_UNUSED;6364void estimate_wind(void);6566// is the AHRS subsystem healthy?67bool healthy() const override;6869bool get_velocity_NED(Vector3f &vec) const override;7071// Get a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.72// 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.73bool get_vert_pos_rate_D(float &velocity) const override;7475// returns false if we fail arming checks, in which case the buffer will be populated with a failure message76// requires_position should be true if horizontal position configuration should be checked (not used)77bool pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const override;7879// relative-origin functions for fallback in AP_InertialNav80bool get_origin(Location &ret) const override;81bool get_relative_position_NED_origin(Vector3f &vec) const override;82bool get_relative_position_NE_origin(Vector2f &posNE) const override;83bool get_relative_position_D_origin(float &posD) const override;8485bool get_filter_status(nav_filter_status &status) const override;86void send_ekf_status_report(class GCS_MAVLINK &link) const override;8788void get_control_limits(float &ekfGndSpdLimit, float &controlScaleXY) const override;89};9091#endif929394