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.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/*15support for serial connected AHRS systems16*/1718#pragma once1920#include "AP_ExternalAHRS_config.h"2122#if HAL_EXTERNAL_AHRS_ENABLED2324#include <AP_HAL/AP_HAL.h>25#include <AP_Param/AP_Param.h>26#include <AP_Common/Location.h>27#include <AP_NavEKF/AP_Nav_Common.h>28#include <AP_GPS/AP_GPS_FixType.h>2930class AP_ExternalAHRS_backend;3132class AP_ExternalAHRS {3334public:35friend class AP_ExternalAHRS_backend;36friend class AP_ExternalAHRS_VectorNav;3738AP_ExternalAHRS();3940void init(void);4142static const struct AP_Param::GroupInfo var_info[];4344enum class DevType : uint8_t {45None = 0,46#if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED47VecNav = 1,48#endif49#if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED50MicroStrain5 = 2,51#endif52#if AP_EXTERNAL_AHRS_INERTIALLABS_ENABLED53InertialLabs = 5,54#endif55// 3 reserved for AdNav56// 4 reserved for CINS57// 6 reserved for Trimble58#if AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED59MicroStrain7 = 7,60#endif61// 8 reserved for SBG62// 9 reserved for EulerNav63// 10 reserved for Aeron64};6566static AP_ExternalAHRS *get_singleton(void) {67return _singleton;68}6970// expected IMU rate in Hz71float get_IMU_rate(void) const {72return rate.get();73}7475// Get model/type name76const char* get_name() const;7778enum class AvailableSensor {79GPS = (1U<<0),80IMU = (1U<<1),81BARO = (1U<<2),82COMPASS = (1U<<3),83};8485// get serial port number, -1 for not enabled86int8_t get_port(AvailableSensor sensor) const;8788struct state_t {89HAL_Semaphore sem;9091Vector3f accel;92Vector3f gyro;93Quaternion quat; // NED94Location location;95Vector3f velocity;96Location origin;9798bool have_quaternion;99bool have_origin;100bool have_location;101bool have_velocity;102103uint32_t last_location_update_us;104} state;105106// accessors for AP_AHRS107bool enabled() const;108bool healthy(void) const;109bool initialised(void) const;110bool get_quaternion(Quaternion &quat);111bool get_origin(Location &loc);112bool set_origin(const Location &loc);113bool get_location(Location &loc);114Vector2f get_groundspeed_vector();115bool get_velocity_NED(Vector3f &vel);116bool get_speed_down(float &speedD);117bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const;118void get_filter_status(nav_filter_status &status) const;119bool get_gyro(Vector3f &gyro);120bool get_accel(Vector3f &accel);121void send_status_report(class GCS_MAVLINK &link) const;122bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const;123124// update backend125void update();126127/*128structures passed to other subsystems129*/130typedef struct {131uint8_t instance;132float pressure_pa;133float temperature;134} baro_data_message_t;135136typedef struct {137Vector3f field;138} mag_data_message_t;139140typedef struct {141uint16_t gps_week;142uint32_t ms_tow;143AP_GPS_FixType fix_type;144uint8_t satellites_in_view;145float horizontal_pos_accuracy;146float vertical_pos_accuracy;147float horizontal_vel_accuracy;148float hdop;149float vdop;150int32_t longitude;151int32_t latitude;152int32_t msl_altitude; // cm153float ned_vel_north;154float ned_vel_east;155float ned_vel_down;156} gps_data_message_t;157158typedef struct {159Vector3f accel;160Vector3f gyro;161float temperature;162} ins_data_message_t;163164typedef struct {165float differential_pressure; // Pa166float temperature; // degC167} airspeed_data_message_t;168169// set GNSS disable for auxillary function GPS_DISABLE170void set_gnss_disable(bool disable) {171gnss_is_disabled = disable;172}173174protected:175176enum class OPTIONS {177VN_UNCOMP_IMU = 1U << 0,178};179bool option_is_set(OPTIONS option) const { return (options.get() & int32_t(option)) != 0; }180181private:182AP_ExternalAHRS_backend *backend;183184AP_Enum<DevType> devtype;185AP_Int16 rate;186AP_Int16 log_rate;187AP_Int16 options;188AP_Int16 sensors;189190static AP_ExternalAHRS *_singleton;191192// check if a sensor type is enabled193bool has_sensor(AvailableSensor sensor) const {194return (uint16_t(sensors.get()) & uint16_t(sensor)) != 0;195}196197// set default of EAHRS_SENSORS198void set_default_sensors(uint16_t _sensors) {199sensors.set_default(_sensors);200}201202uint32_t last_log_ms;203204// true when user has disabled the GNSS205bool gnss_is_disabled;206};207208namespace AP {209AP_ExternalAHRS &externalAHRS();210};211212#endif // HAL_EXTERNAL_AHRS_ENABLED213214215216