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_AHRS/AP_AHRS_Backend.h
Views: 1798
1
#pragma once
2
3
/*
4
This program is free software: you can redistribute it and/or modify
5
it under the terms of the GNU General Public License as published by
6
the Free Software Foundation, either version 3 of the License, or
7
(at your option) any later version.
8
9
This program is distributed in the hope that it will be useful,
10
but WITHOUT ANY WARRANTY; without even the implied warranty of
11
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12
GNU General Public License for more details.
13
14
You should have received a copy of the GNU General Public License
15
along with this program. If not, see <http://www.gnu.org/licenses/>.
16
*/
17
18
/*
19
* AHRS (Attitude Heading Reference System) interface for ArduPilot
20
*
21
*/
22
23
#include <AP_Math/AP_Math.h>
24
#include <inttypes.h>
25
#include <AP_Airspeed/AP_Airspeed.h>
26
#include <AP_InertialSensor/AP_InertialSensor.h>
27
#include <AP_Common/Location.h>
28
#include <AP_NavEKF/AP_NavEKF_Source.h>
29
30
#define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees
31
#define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter
32
#define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter
33
34
enum class GPSUse : uint8_t {
35
Disable = 0,
36
Enable = 1,
37
EnableWithHeight = 2,
38
};
39
40
class AP_AHRS_Backend
41
{
42
public:
43
44
// Constructor
45
AP_AHRS_Backend() {}
46
47
// empty virtual destructor
48
virtual ~AP_AHRS_Backend() {}
49
50
CLASS_NO_COPY(AP_AHRS_Backend);
51
52
// structure to retrieve results from backends:
53
struct Estimates {
54
float roll_rad;
55
float pitch_rad;
56
float yaw_rad;
57
Matrix3f dcm_matrix;
58
Vector3f gyro_estimate;
59
Vector3f gyro_drift;
60
Vector3f accel_ef;
61
Vector3f accel_bias;
62
63
Location location;
64
bool location_valid;
65
66
bool get_location(Location &loc) const {
67
loc = location;
68
return location_valid;
69
};
70
};
71
72
// init sets up INS board orientation
73
virtual void init();
74
75
// get the index of the current primary gyro sensor
76
virtual uint8_t get_primary_gyro_index(void) const {
77
#if AP_INERTIALSENSOR_ENABLED
78
return AP::ins().get_first_usable_gyro();
79
#else
80
return 0;
81
#endif
82
}
83
84
// Methods
85
virtual void update() = 0;
86
87
virtual void get_results(Estimates &results) = 0;
88
89
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
90
// requires_position should be true if horizontal position configuration should be checked
91
virtual bool pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const = 0;
92
93
// check all cores providing consistent attitudes for prearm checks
94
virtual bool attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const { return true; }
95
96
// see if EKF lane switching is possible to avoid EKF failsafe
97
virtual void check_lane_switch(void) {}
98
99
// check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed
100
virtual bool using_noncompass_for_yaw(void) const { return false; }
101
102
// check if external nav is providing yaw
103
virtual bool using_extnav_for_yaw(void) const { return false; }
104
105
// request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe
106
virtual void request_yaw_reset(void) {}
107
108
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
109
virtual void set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx) {}
110
111
// reset the current gyro drift estimate
112
// should be called if gyro offsets are recalculated
113
virtual void reset_gyro_drift(void) = 0;
114
115
// reset the current attitude, used on new IMU calibration
116
virtual void reset() = 0;
117
118
// get latest altitude estimate above ground level in meters and validity flag
119
virtual bool get_hagl(float &height) const WARN_IF_UNUSED { return false; }
120
121
// return a wind estimation vector, in m/s
122
virtual bool wind_estimate(Vector3f &wind) const = 0;
123
124
// return an airspeed estimate if available. return true
125
// if we have an estimate
126
virtual bool airspeed_EAS(float &airspeed_ret) const WARN_IF_UNUSED { return false; }
127
virtual bool airspeed_EAS(uint8_t airspeed_index, float &airspeed_ret) const { return false; }
128
129
// return a true airspeed estimate (navigation airspeed) if
130
// available. return true if we have an estimate
131
bool airspeed_TAS(float &airspeed_ret) const WARN_IF_UNUSED {
132
if (!airspeed_EAS(airspeed_ret)) {
133
return false;
134
}
135
airspeed_ret *= get_EAS2TAS();
136
return true;
137
}
138
139
// get apparent to true airspeed ratio
140
static float get_EAS2TAS(void);
141
static float get_TAS2EAS(void) { return 1.0/get_EAS2TAS(); }
142
143
// return true if airspeed comes from an airspeed sensor, as
144
// opposed to an IMU estimate
145
static bool airspeed_sensor_enabled(void) {
146
#if AP_AIRSPEED_ENABLED
147
const AP_Airspeed *_airspeed = AP::airspeed();
148
return _airspeed != nullptr && _airspeed->use() && _airspeed->healthy();
149
#else
150
return false;
151
#endif
152
}
153
154
// return true if airspeed comes from a specific airspeed sensor, as
155
// opposed to an IMU estimate
156
static bool airspeed_sensor_enabled(uint8_t airspeed_index) {
157
#if AP_AIRSPEED_ENABLED
158
const AP_Airspeed *_airspeed = AP::airspeed();
159
return _airspeed != nullptr && _airspeed->use(airspeed_index) && _airspeed->healthy(airspeed_index);
160
#else
161
return false;
162
#endif
163
}
164
165
// return a ground vector estimate in meters/second, in North/East order
166
virtual Vector2f groundspeed_vector(void) = 0;
167
168
// return a ground velocity in meters/second, North/East/Down
169
// order. This will only be accurate if have_inertial_nav() is
170
// true
171
virtual bool get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED {
172
return false;
173
}
174
175
// Get a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.
176
// 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.
177
virtual bool get_vert_pos_rate_D(float &velocity) const = 0;
178
179
//
180
virtual bool set_origin(const Location &loc) {
181
return false;
182
}
183
virtual bool get_origin(Location &ret) const = 0;
184
185
// return a position relative to origin in meters, North/East/Down
186
// order. This will only be accurate if have_inertial_nav() is
187
// true
188
virtual bool get_relative_position_NED_origin(Vector3f &vec) const WARN_IF_UNUSED {
189
return false;
190
}
191
192
// return a position relative to origin in meters, North/East
193
// order. Return true if estimate is valid
194
virtual bool get_relative_position_NE_origin(Vector2f &vecNE) const WARN_IF_UNUSED {
195
return false;
196
}
197
198
// return a Down position relative to origin in meters
199
// Return true if estimate is valid
200
virtual bool get_relative_position_D_origin(float &posD) const WARN_IF_UNUSED {
201
return false;
202
}
203
204
// return ground speed estimate in meters/second. Used by ground vehicles.
205
float groundspeed(void) {
206
return groundspeed_vector().length();
207
}
208
209
// return true if we will use compass for yaw
210
virtual bool use_compass(void) = 0;
211
212
// return the quaternion defining the rotation from NED to XYZ (body) axes
213
virtual bool get_quaternion(Quaternion &quat) const WARN_IF_UNUSED = 0;
214
215
// is the AHRS subsystem healthy?
216
virtual bool healthy(void) const = 0;
217
218
// true if the AHRS has completed initialisation
219
virtual bool initialised(void) const {
220
return true;
221
};
222
virtual bool started(void) const {
223
return initialised();
224
};
225
226
// return the amount of yaw angle change due to the last yaw angle reset in radians
227
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
228
virtual uint32_t getLastYawResetAngle(float &yawAng) {
229
return 0;
230
};
231
232
// return the amount of NE position change in metres due to the last reset
233
// returns the time of the last reset or 0 if no reset has ever occurred
234
virtual uint32_t getLastPosNorthEastReset(Vector2f &pos) WARN_IF_UNUSED {
235
return 0;
236
};
237
238
// return the amount of NE velocity change in metres/sec due to the last reset
239
// returns the time of the last reset or 0 if no reset has ever occurred
240
virtual uint32_t getLastVelNorthEastReset(Vector2f &vel) const WARN_IF_UNUSED {
241
return 0;
242
};
243
244
// return the amount of vertical position change due to the last reset in meters
245
// returns the time of the last reset or 0 if no reset has ever occurred
246
virtual uint32_t getLastPosDownReset(float &posDelta) WARN_IF_UNUSED {
247
return 0;
248
};
249
250
// Resets the baro so that it reads zero at the current height
251
// Resets the EKF height to zero
252
// Adjusts the EKf origin height so that the EKF height + origin height is the same as before
253
// Returns true if the height datum reset has been performed
254
// If using a range finder for height no reset is performed and it returns false
255
virtual bool resetHeightDatum(void) WARN_IF_UNUSED {
256
return false;
257
}
258
259
// return the innovations for the specified instance
260
// An out of range instance (eg -1) returns data for the primary instance
261
virtual bool get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const {
262
return false;
263
}
264
265
virtual bool get_filter_status(union nav_filter_status &status) const {
266
return false;
267
}
268
269
// get_variances - provides the innovations normalised using the innovation variance where a value of 0
270
// indicates perfect consistency between the measurement and the EKF solution and a value of 1 is the maximum
271
// inconsistency that will be accepted by the filter
272
// boolean false is returned if variances are not available
273
virtual bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const {
274
return false;
275
}
276
277
// get a source's velocity innovations. source should be from 0 to 7 (see AP_NavEKF_Source::SourceXY)
278
// returns true on success and results are placed in innovations and variances arguments
279
virtual bool get_vel_innovations_and_variances_for_source(uint8_t source, Vector3f &innovations, Vector3f &variances) const WARN_IF_UNUSED {
280
return false;
281
}
282
283
virtual void send_ekf_status_report(class GCS_MAVLINK &link) const = 0;
284
285
// get_hgt_ctrl_limit - get maximum height to be observed by the
286
// control loops in meters and a validity flag. It will return
287
// false when no limiting is required
288
virtual bool get_hgt_ctrl_limit(float &limit) const WARN_IF_UNUSED { return false; };
289
290
// Set to true if the terrain underneath is stable enough to be used as a height reference
291
// this is not related to terrain following
292
virtual void set_terrain_hgt_stable(bool stable) {}
293
294
virtual void get_control_limits(float &ekfGndSpdLimit, float &controlScaleXY) const = 0;
295
};
296
297