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_ExternalAHRS/AP_ExternalAHRS_backend.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15parent class for ExternalAHRS backends16*/1718#pragma once1920#include "AP_ExternalAHRS.h"2122#if HAL_EXTERNAL_AHRS_ENABLED2324class AP_ExternalAHRS_backend {25public:26AP_ExternalAHRS_backend(AP_ExternalAHRS *frontend, AP_ExternalAHRS::state_t &state);2728// get serial port number, -1 for not enabled29virtual int8_t get_port(void) const { return -1; }3031// Get model/type name32virtual const char* get_name() const = 0;3334// Accessors for AP_AHRS3536// If not healthy, none of the other API's can be trusted.37// Example: Serial cable is severed.38virtual bool healthy(void) const = 0;39// The communication interface is up and the device has sent valid data.40virtual bool initialised(void) const = 0;41virtual bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const = 0;42virtual void get_filter_status(nav_filter_status &status) const {}43virtual bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const { return false; }4445// Check for new data.46// This is used when there's not a separate thread for EAHRS.47// This can also copy interim state protected by locking.48virtual void update() = 0;4950// Return the number of GPS sensors sharing data to AP_GPS.51virtual uint8_t num_gps_sensors(void) const = 0;5253protected:54AP_ExternalAHRS::state_t &state;55uint16_t get_rate(void) const;56bool option_is_set(AP_ExternalAHRS::OPTIONS option) const;5758// set default of EAHRS_SENSORS59void set_default_sensors(uint16_t sensors) {60frontend.set_default_sensors(sensors);61}6263/*64return true if the GNSS is disabled65*/66bool gnss_is_disabled(void) const {67return frontend.gnss_is_disabled;68}6970/*71return true when we are in fixed wing flight72*/73bool in_fly_forward(void) const;7475/*76scale factors for get_variances() to return normalised values from SI units77*/78const float vel_gate_scale = 0.2;79const float pos_gate_scale = 0.2;80const float hgt_gate_scale = 0.2;8182private:83AP_ExternalAHRS &frontend;84};8586#endif // HAL_EXTERNAL_AHRS_ENABLED87888990