CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_DAL/AP_DAL_GPS.h
Views: 1798
1
#pragma once
2
3
#include <AP_GPS/AP_GPS.h>
4
5
#include <AP_Logger/LogStructure.h>
6
7
class AP_DAL_GPS {
8
public:
9
10
/// GPS status codes
11
enum GPS_Status : uint8_t {
12
NO_GPS = GPS_FIX_TYPE_NO_GPS, ///< No GPS connected/detected
13
NO_FIX = GPS_FIX_TYPE_NO_FIX, ///< Receiving valid GPS messages but no lock
14
GPS_OK_FIX_2D = GPS_FIX_TYPE_2D_FIX, ///< Receiving valid messages and 2D lock
15
GPS_OK_FIX_3D = GPS_FIX_TYPE_3D_FIX, ///< Receiving valid messages and 3D lock
16
GPS_OK_FIX_3D_DGPS = GPS_FIX_TYPE_DGPS, ///< Receiving valid messages and 3D lock with differential improvements
17
GPS_OK_FIX_3D_RTK_FLOAT = GPS_FIX_TYPE_RTK_FLOAT, ///< Receiving valid messages and 3D RTK Float
18
GPS_OK_FIX_3D_RTK_FIXED = GPS_FIX_TYPE_RTK_FIXED, ///< Receiving valid messages and 3D RTK Fixed
19
};
20
21
AP_DAL_GPS();
22
23
GPS_Status status(uint8_t sensor_id) const {
24
return (GPS_Status)_RGPI[sensor_id].status;
25
}
26
GPS_Status status() const {
27
return status(primary_sensor());
28
}
29
const Location &location(uint8_t instance) const {
30
return tmp_location[instance];
31
}
32
bool have_vertical_velocity(uint8_t instance) const {
33
return _RGPI[instance].have_vertical_velocity;
34
}
35
bool have_vertical_velocity() const {
36
return have_vertical_velocity(primary_sensor());
37
}
38
bool horizontal_accuracy(uint8_t instance, float &hacc) const {
39
hacc = _RGPJ[instance].hacc;
40
return _RGPI[instance].horizontal_accuracy_returncode;
41
}
42
bool horizontal_accuracy(float &hacc) const {
43
return horizontal_accuracy(primary_sensor(),hacc);
44
}
45
46
bool vertical_accuracy(uint8_t instance, float &vacc) const {
47
vacc = _RGPJ[instance].vacc;
48
return _RGPI[instance].vertical_accuracy_returncode;
49
}
50
bool vertical_accuracy(float &vacc) const {
51
return vertical_accuracy(primary_sensor(), vacc);
52
}
53
54
uint16_t get_hdop(uint8_t instance) const {
55
return _RGPJ[instance].hdop;
56
}
57
uint16_t get_hdop() const {
58
return get_hdop(primary_sensor());
59
}
60
61
uint32_t last_message_time_ms(uint8_t instance) const {
62
return _RGPJ[instance].last_message_time_ms;
63
}
64
65
uint8_t num_sats(uint8_t instance) const {
66
return _RGPI[instance].num_sats;
67
}
68
uint8_t num_sats() const {
69
return num_sats(primary_sensor());
70
}
71
72
bool get_lag(uint8_t instance, float &lag_sec) const {
73
lag_sec = _RGPI[instance].lag_sec;
74
return _RGPI[instance].get_lag_returncode;
75
}
76
bool get_lag(float &lag_sec) const {
77
return get_lag(primary_sensor(), lag_sec);
78
}
79
80
const Vector3f &velocity(uint8_t instance) const {
81
return _RGPJ[instance].velocity;
82
}
83
const Vector3f &velocity() const {
84
return velocity(primary_sensor());
85
}
86
87
bool speed_accuracy(uint8_t instance, float &sacc) const {
88
sacc = _RGPJ[instance].sacc;
89
return _RGPI[instance].speed_accuracy_returncode;
90
}
91
bool speed_accuracy(float &sacc) const {
92
return speed_accuracy(primary_sensor(), sacc);
93
}
94
95
bool gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, uint32_t &time_ms) const {
96
yaw_deg = _RGPJ[instance].yaw_deg;
97
accuracy_deg = _RGPJ[instance].yaw_accuracy_deg;
98
time_ms = _RGPJ[instance].yaw_deg_time_ms;
99
return _RGPI[instance].gps_yaw_deg_returncode;
100
}
101
102
uint8_t num_sensors(void) const {
103
return _RGPH.num_sensors;
104
}
105
106
uint8_t primary_sensor(void) const {
107
return _RGPH.primary_sensor;
108
}
109
110
// TODO: decide if this really, really should be here!
111
const Location &location() const {
112
return location(_RGPH.primary_sensor);
113
}
114
115
// return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin
116
const Vector3f &get_antenna_offset(uint8_t instance) const {
117
return _RGPI[instance].antenna_offset;
118
}
119
120
void start_frame();
121
122
void handle_message(const log_RGPH &msg) {
123
_RGPH = msg;
124
}
125
void handle_message(const log_RGPI &msg) {
126
_RGPI[msg.instance] = msg;
127
}
128
void handle_message(const log_RGPJ &msg) {
129
_RGPJ[msg.instance] = msg;
130
131
tmp_location[msg.instance].lat = msg.lat;
132
tmp_location[msg.instance].lng = msg.lng;
133
tmp_location[msg.instance].alt = msg.alt;
134
}
135
136
private:
137
138
struct log_RGPH _RGPH;
139
struct log_RGPI _RGPI[GPS_MAX_INSTANCES];
140
struct log_RGPJ _RGPJ[GPS_MAX_INSTANCES];
141
142
Location tmp_location[GPS_MAX_INSTANCES];
143
};
144
145