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_DAL/AP_DAL_GPS.h
Views: 1798
#pragma once12#include <AP_GPS/AP_GPS.h>34#include <AP_Logger/LogStructure.h>56class AP_DAL_GPS {7public:89/// GPS status codes10enum GPS_Status : uint8_t {11NO_GPS = GPS_FIX_TYPE_NO_GPS, ///< No GPS connected/detected12NO_FIX = GPS_FIX_TYPE_NO_FIX, ///< Receiving valid GPS messages but no lock13GPS_OK_FIX_2D = GPS_FIX_TYPE_2D_FIX, ///< Receiving valid messages and 2D lock14GPS_OK_FIX_3D = GPS_FIX_TYPE_3D_FIX, ///< Receiving valid messages and 3D lock15GPS_OK_FIX_3D_DGPS = GPS_FIX_TYPE_DGPS, ///< Receiving valid messages and 3D lock with differential improvements16GPS_OK_FIX_3D_RTK_FLOAT = GPS_FIX_TYPE_RTK_FLOAT, ///< Receiving valid messages and 3D RTK Float17GPS_OK_FIX_3D_RTK_FIXED = GPS_FIX_TYPE_RTK_FIXED, ///< Receiving valid messages and 3D RTK Fixed18};1920AP_DAL_GPS();2122GPS_Status status(uint8_t sensor_id) const {23return (GPS_Status)_RGPI[sensor_id].status;24}25GPS_Status status() const {26return status(primary_sensor());27}28const Location &location(uint8_t instance) const {29return tmp_location[instance];30}31bool have_vertical_velocity(uint8_t instance) const {32return _RGPI[instance].have_vertical_velocity;33}34bool have_vertical_velocity() const {35return have_vertical_velocity(primary_sensor());36}37bool horizontal_accuracy(uint8_t instance, float &hacc) const {38hacc = _RGPJ[instance].hacc;39return _RGPI[instance].horizontal_accuracy_returncode;40}41bool horizontal_accuracy(float &hacc) const {42return horizontal_accuracy(primary_sensor(),hacc);43}4445bool vertical_accuracy(uint8_t instance, float &vacc) const {46vacc = _RGPJ[instance].vacc;47return _RGPI[instance].vertical_accuracy_returncode;48}49bool vertical_accuracy(float &vacc) const {50return vertical_accuracy(primary_sensor(), vacc);51}5253uint16_t get_hdop(uint8_t instance) const {54return _RGPJ[instance].hdop;55}56uint16_t get_hdop() const {57return get_hdop(primary_sensor());58}5960uint32_t last_message_time_ms(uint8_t instance) const {61return _RGPJ[instance].last_message_time_ms;62}6364uint8_t num_sats(uint8_t instance) const {65return _RGPI[instance].num_sats;66}67uint8_t num_sats() const {68return num_sats(primary_sensor());69}7071bool get_lag(uint8_t instance, float &lag_sec) const {72lag_sec = _RGPI[instance].lag_sec;73return _RGPI[instance].get_lag_returncode;74}75bool get_lag(float &lag_sec) const {76return get_lag(primary_sensor(), lag_sec);77}7879const Vector3f &velocity(uint8_t instance) const {80return _RGPJ[instance].velocity;81}82const Vector3f &velocity() const {83return velocity(primary_sensor());84}8586bool speed_accuracy(uint8_t instance, float &sacc) const {87sacc = _RGPJ[instance].sacc;88return _RGPI[instance].speed_accuracy_returncode;89}90bool speed_accuracy(float &sacc) const {91return speed_accuracy(primary_sensor(), sacc);92}9394bool gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, uint32_t &time_ms) const {95yaw_deg = _RGPJ[instance].yaw_deg;96accuracy_deg = _RGPJ[instance].yaw_accuracy_deg;97time_ms = _RGPJ[instance].yaw_deg_time_ms;98return _RGPI[instance].gps_yaw_deg_returncode;99}100101uint8_t num_sensors(void) const {102return _RGPH.num_sensors;103}104105uint8_t primary_sensor(void) const {106return _RGPH.primary_sensor;107}108109// TODO: decide if this really, really should be here!110const Location &location() const {111return location(_RGPH.primary_sensor);112}113114// return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin115const Vector3f &get_antenna_offset(uint8_t instance) const {116return _RGPI[instance].antenna_offset;117}118119void start_frame();120121void handle_message(const log_RGPH &msg) {122_RGPH = msg;123}124void handle_message(const log_RGPI &msg) {125_RGPI[msg.instance] = msg;126}127void handle_message(const log_RGPJ &msg) {128_RGPJ[msg.instance] = msg;129130tmp_location[msg.instance].lat = msg.lat;131tmp_location[msg.instance].lng = msg.lng;132tmp_location[msg.instance].alt = msg.alt;133}134135private:136137struct log_RGPH _RGPH;138struct log_RGPI _RGPI[GPS_MAX_INSTANCES];139struct log_RGPJ _RGPJ[GPS_MAX_INSTANCES];140141Location tmp_location[GPS_MAX_INSTANCES];142};143144145