Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_AHRS/AP_AHRS.h
9710 views
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) frontend interface for
20
* ArduPilot
21
*
22
*/
23
24
#include "AP_AHRS_config.h"
25
26
#include <AP_HAL/Semaphores.h>
27
28
#include "AP_AHRS_Backend.h"
29
#include <AP_NavEKF2/AP_NavEKF2.h>
30
#include <AP_NavEKF3/AP_NavEKF3.h>
31
#include <AP_NavEKF/AP_Nav_Common.h> // definitions shared by inertial and ekf nav filters
32
33
#include "AP_AHRS_DCM.h"
34
#include "AP_AHRS_SIM.h"
35
#include "AP_AHRS_External.h"
36
37
// forward declare view class
38
class AP_AHRS_View;
39
40
#define AP_AHRS_NAVEKF_SETTLE_TIME_MS 20000 // time in milliseconds the ekf needs to settle after being started
41
42
43
// fwd declare GSF estimator
44
class EKFGSF_yaw;
45
46
class AP_AHRS {
47
friend class AP_AHRS_View;
48
public:
49
50
// copy this into our namespace
51
using Status = NavFilterStatusBit;
52
53
enum Flags {
54
FLAG_ALWAYS_USE_EKF = 0x1,
55
};
56
57
// has_status returns information about the EKF health and
58
// capabilities. It is currently invalid to call this when a
59
// backend is in charge which returns false for get_filter_status
60
// - so this will simply return false for DCM, for example.
61
bool has_status(Status status) const;
62
63
// Constructor
64
AP_AHRS(uint8_t flags = 0);
65
66
// initialise
67
void init(void);
68
69
/* Do not allow copies */
70
CLASS_NO_COPY(AP_AHRS);
71
72
// get singleton instance
73
static AP_AHRS *get_singleton() {
74
return _singleton;
75
}
76
77
// periodically checks to see if we should update the AHRS
78
// orientation (e.g. based on the AHRS_ORIENTATION parameter)
79
// allow for runtime change of orientation
80
// this makes initial config easier
81
void update_orientation();
82
83
// allow threads to lock against AHRS update
84
HAL_Semaphore &get_semaphore(void) {
85
return _rsem;
86
}
87
88
// return the smoothed gyro vector corrected for drift
89
const Vector3f &get_gyro(void) const { return state.gyro_estimate; }
90
91
// return the current drift correction integrator value
92
const Vector3f &get_gyro_drift(void) const { return state.gyro_drift; }
93
94
// reset the current gyro drift estimate
95
// should be called if gyro offsets are recalculated
96
void reset_gyro_drift();
97
98
void update(bool skip_ins_update=false);
99
void reset();
100
101
// get current location estimate
102
bool get_location(Location &loc) const;
103
104
// get latest altitude estimate above ground level in meters and validity flag
105
bool get_hagl(float &hagl) const WARN_IF_UNUSED;
106
107
// status reporting of estimated error
108
float get_error_rp() const;
109
float get_error_yaw() const;
110
111
/*
112
* wind estimation support
113
*/
114
115
// enable wind estimation
116
void set_wind_estimation_enabled(bool b) { wind_estimation_enabled = b; }
117
118
// wind_estimation_enabled returns true if wind estimation is enabled
119
bool get_wind_estimation_enabled() const { return wind_estimation_enabled; }
120
121
// return a wind estimation vector, in m/s; returns 0,0,0 on failure
122
const Vector3f &wind_estimate() const { return state.wind_estimate; }
123
124
// return a wind estimation vector, in m/s; returns 0,0,0 on failure
125
bool wind_estimate(Vector3f &wind) const;
126
127
// Determine how aligned heading_deg is with the wind. Return result
128
// is 1.0 when perfectly aligned heading into wind, -1 when perfectly
129
// aligned with-wind, and zero when perfect cross-wind. There is no
130
// distinction between a left or right cross-wind. Wind speed is ignored
131
float wind_alignment(const float heading_deg) const;
132
133
// returns forward head-wind component in m/s. Negative means tail-wind
134
float head_wind(void) const;
135
136
// instruct DCM to update its wind estimate:
137
void estimate_wind() {
138
#if AP_AHRS_DCM_ENABLED
139
dcm.estimate_wind();
140
#endif
141
}
142
143
#if AP_AHRS_EXTERNAL_WIND_ESTIMATE_ENABLED
144
void set_external_wind_estimate(float speed, float direction) {
145
dcm.set_external_wind_estimate(speed, direction);
146
}
147
#endif
148
149
// return the parameter AHRS_WIND_MAX in metres per second
150
uint8_t get_max_wind() const {
151
return _wind_max;
152
}
153
154
/*
155
* airspeed support
156
*/
157
158
// get apparent to true airspeed ratio
159
float get_EAS2TAS(void) const;
160
161
// get air density / sea level density - decreases as altitude climbs
162
float get_air_density_ratio(void) const;
163
164
// return an (equivalent) airspeed estimate if available. return
165
// true if airspeed_ret is valid. This value may be derived from
166
// airspeed data or synthesised from other sources.
167
bool airspeed_EAS(float &airspeed_ret) const;
168
169
enum AirspeedEstimateType : uint8_t {
170
NO_NEW_ESTIMATE = 0,
171
AIRSPEED_SENSOR = 1,
172
DCM_SYNTHETIC = 2,
173
EKF3_SYNTHETIC = 3,
174
SIM = 4,
175
};
176
177
// return an (equivalent) airspeed estimate if available. return
178
// true if airspeed_ret is valid. This value may be derived from
179
// airspeed data or synthesised from other sources (the type
180
// return parameter allows you to distinguish).
181
bool airspeed_EAS(float &airspeed_ret, AirspeedEstimateType &type) const;
182
183
// return true if the current AHRS airspeed estimate (from airspeed_estimate method) is directly derived from an airspeed sensor
184
bool using_airspeed_sensor() const;
185
186
// return a true airspeed (navigation airspeed) if
187
// available. return true if airspeed_ret is valid. This value
188
// may be derived from actual airspeed sensor data or synthesized
189
// from other sources.
190
bool airspeed_TAS(float &airspeed_ret) const;
191
192
// return estimate of true airspeed vector in body frame in m/s
193
// returns false if estimate is unavailable
194
bool airspeed_vector_TAS(Vector3f &vec) const;
195
196
// return the innovation in m/s, innovation variance in (m/s)^2 and age in msec of the last TAS measurement processed for a given sensor instance
197
// returns false if the data is unavailable
198
bool airspeed_health_data(uint8_t instance, float &innovation, float &innovationVariance, uint32_t &age_ms) const;
199
200
// return true if a airspeed sensor is enabled
201
bool airspeed_sensor_enabled(void) const {
202
// FIXME: make this a method on the active backend
203
return AP_AHRS_Backend::airspeed_sensor_enabled();
204
}
205
206
// return true if a airspeed from a specific airspeed sensor is enabled
207
bool airspeed_sensor_enabled(uint8_t airspeed_index) const {
208
// FIXME: make this a method on the active backend
209
return AP_AHRS_Backend::airspeed_sensor_enabled(airspeed_index);
210
}
211
212
// true if compass is being used
213
bool use_compass();
214
215
// return the quaternion defining the rotation from NED to XYZ (body) axes
216
bool get_quaternion(Quaternion &quat) const WARN_IF_UNUSED;
217
218
// return secondary attitude solution if available, as eulers in radians
219
bool get_secondary_attitude(Vector3f &eulers) const {
220
eulers = state.secondary_attitude;
221
return state.secondary_attitude_ok;
222
}
223
224
// return secondary attitude solution if available, as quaternion
225
bool get_secondary_quaternion(Quaternion &quat) const {
226
quat = state.secondary_quat;
227
return state.secondary_quat_ok;
228
}
229
230
// return secondary position solution if available
231
bool get_secondary_position(Location &loc) const {
232
loc = state.secondary_pos;
233
return state.secondary_pos_ok;
234
}
235
236
// EKF has a better ground speed vector estimate
237
const Vector2f &groundspeed_vector() const { return state.ground_speed_vec; }
238
239
// return ground speed estimate in meters/second. Used by ground vehicles.
240
float groundspeed(void) const { return state.ground_speed; }
241
242
const Vector3f &get_accel_ef() const {
243
return state.accel_ef;
244
}
245
246
// Retrieves the corrected NED delta velocity in use by the inertial navigation
247
void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const {
248
ret = state.corrected_dv;
249
dt = state.corrected_dv_dt;
250
}
251
252
// set the EKF's origin location in 10e7 degrees. This should only
253
// be called when the EKF has no absolute position reference (i.e. GPS)
254
// from which to decide the origin on its own
255
bool set_origin(const Location &loc) WARN_IF_UNUSED;
256
257
// Set the origin to the last recorded location if option bit set and not using GPS
258
// This is useful for position controlled modes without GPS
259
void use_recorded_origin_maybe();
260
261
#if AP_AHRS_POSITION_RESET_ENABLED
262
// Set the EKF's NE horizontal position states and their corresponding variances from the supplied WGS-84 location
263
// and 1-sigma horizontal position uncertainty. This can be used when the EKF is dead reckoning to periodically
264
// correct the position. If the EKF is is still using data from a position sensor such as GPS, the position set
265
// will not be performed.
266
// pos_accuracy is the standard deviation of the horizontal position uncertainty in metres.
267
// The altitude element of the location is not used.
268
// Returns true if the set was successful.
269
bool handle_external_position_estimate(const Location &loc, float pos_accuracy, uint32_t timestamp_);
270
#endif
271
272
// returns the inertial navigation origin in lat/lon/alt
273
bool get_origin(Location &ret) const WARN_IF_UNUSED;
274
275
bool have_inertial_nav() const;
276
277
// return a ground velocity in meters/second, North/East/Down
278
// order. Must only be called if have_inertial_nav() is true
279
bool get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED;
280
281
// return the relative position NED from either home or origin
282
// return true if the estimate is valid
283
bool get_relative_position_NED_home(Vector3f &vec) const WARN_IF_UNUSED;
284
bool get_relative_position_NED_origin(Vector3p &vec) const WARN_IF_UNUSED;
285
bool get_relative_position_NED_origin_float(Vector3f &vec) const WARN_IF_UNUSED;
286
287
// return the relative position NE from home or origin
288
// return true if the estimate is valid
289
bool get_relative_position_NE_home(Vector2f &posNE) const WARN_IF_UNUSED;
290
bool get_relative_position_NE_origin(Vector2p &posNE) const WARN_IF_UNUSED;
291
bool get_relative_position_NE_origin_float(Vector2f &posNE) const WARN_IF_UNUSED;
292
293
// return the relative position down from home or origin
294
// baro will be used for the _home relative one if the EKF isn't
295
void get_relative_position_D_home(float &posD) const;
296
bool get_relative_position_D_origin(postype_t &posD) const WARN_IF_UNUSED;
297
bool get_relative_position_D_origin_float(float &posD) const WARN_IF_UNUSED;
298
299
// return location corresponding to vector relative to the
300
// vehicle's origin
301
bool get_location_from_origin_offset_NED(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED;
302
bool get_location_from_home_offset_NED(Location &loc, const Vector3p &offset_ned) const WARN_IF_UNUSED;
303
304
// get velocity down in m/s. This returns get_velocity_NED.z() if available, otherwise falls back to get_vert_pos_rate_D()
305
// if high_vibes is true then this is equivalent to get_vert_pos_rate_D
306
bool get_velocity_D(float &velD, bool high_vibes = false) const WARN_IF_UNUSED;
307
308
// Get a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.
309
// 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.
310
bool get_vert_pos_rate_D(float &velocity) const;
311
312
// write optical flow measurements to EKF
313
void writeOptFlowMeas(const uint8_t rawFlowQuality, const Vector2f &rawFlowRates, const Vector2f &rawGyroRates, const uint32_t msecFlowMeas, const Vector3f &posOffset, const float heightOverride);
314
315
// retrieve latest corrected optical flow samples (used for calibration)
316
bool getOptFlowSample(uint32_t& timeStamp_ms, Vector2f& flowRate, Vector2f& bodyRate, Vector2f& losPred) const;
317
318
// write body odometry measurements to the EKF
319
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset);
320
321
// Writes the default equivalent airspeed and its 1-sigma uncertainty in m/s to be used in forward flight if a measured airspeed is required and not available.
322
void writeDefaultAirSpeed(float airspeed, float uncertainty);
323
324
// Write position and quaternion data from an external navigation system
325
void writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms);
326
327
// Write velocity data from an external navigation system
328
void writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms);
329
330
// Write terrain (derived from SRTM) altitude in meters above sea level
331
void writeTerrainAMSL(float alt_amsl_m);
332
333
// get speed limit
334
void getControlLimits(float &ekfGndSpdLimit, float &controlScaleXY) const;
335
float getControlScaleZ(void) const;
336
337
// is the AHRS subsystem healthy?
338
bool healthy() const;
339
340
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
341
// requires_position should be true if horizontal position configuration should be checked
342
bool pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const;
343
344
// true if the AHRS has completed initialisation
345
bool initialised() const;
346
347
#if AP_AHRS_DCM_ENABLED
348
// return true if *DCM* yaw has been initialised
349
bool dcm_yaw_initialised(void) const {
350
return dcm.yaw_initialised();
351
}
352
#endif
353
354
// get_filter_status - returns filter status as a series of flags
355
bool get_filter_status(nav_filter_status &status) const;
356
357
// get compass offset estimates
358
// true if offsets are valid
359
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const;
360
361
// return the amount of yaw angle change due to the last yaw angle reset in radians
362
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
363
uint32_t getLastYawResetAngle(float &yawAng);
364
365
// return the amount of NE position change in meters due to the last reset
366
// returns the time of the last reset or 0 if no reset has ever occurred
367
uint32_t getLastPosNorthEastReset(Vector2f &pos);
368
369
// return the amount of NE velocity change in meters/sec due to the last reset
370
// returns the time of the last reset or 0 if no reset has ever occurred
371
uint32_t getLastVelNorthEastReset(Vector2f &vel) const;
372
373
// return the amount of vertical position change due to the last reset in meters
374
// returns the time of the last reset or 0 if no reset has ever occurred
375
uint32_t getLastPosDownReset(float &posDelta);
376
377
// Resets the baro so that it reads zero at the current height
378
// Resets the EKF height to zero
379
// Adjusts the EKf origin height so that the EKF height + origin height is the same as before
380
void resetHeightDatum();
381
382
// send a EKF_STATUS_REPORT for current EKF
383
void send_ekf_status_report(class GCS_MAVLINK &link) const;
384
385
// get_hgt_ctrl_limit - get maximum height to be observed by the control loops in meters and a validity flag
386
// this is used to limit height during optical flow navigation
387
// it will return invalid when no limiting is required
388
bool get_hgt_ctrl_limit(float &limit) const;
389
390
// Set to true if the terrain underneath is stable enough to be used as a height reference
391
// this is not related to terrain following
392
void set_terrain_hgt_stable(bool stable);
393
394
// return the innovations for the specified instance
395
// An out of range instance (eg -1) returns data for the primary instance
396
bool get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const;
397
398
// returns true when the state estimates are significantly degraded by vibration
399
bool is_vibration_affected() const;
400
401
// get_variances - provides the innovations normalised using the innovation variance where a value of 0
402
// indicates perfect consistency between the measurement and the EKF solution and a value of 1 is the maximum
403
// inconsistency that will be accepted by the filter
404
// boolean false is returned if variances are not available
405
bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const;
406
407
// get a source's velocity innovations
408
// returns true on success and results are placed in innovations and variances arguments
409
bool get_vel_innovations_and_variances_for_source(uint8_t source, Vector3f &innovations, Vector3f &variances) const WARN_IF_UNUSED;
410
411
// returns the expected NED magnetic field
412
bool get_mag_field_NED(Vector3f& ret) const;
413
414
// returns the estimated magnetic field offsets in body frame
415
bool get_mag_field_correction(Vector3f &ret) const;
416
417
// return the index of the airspeed we should use for airspeed measurements
418
// with multiple airspeed sensors and airspeed affinity in EKF3, it is possible to have switched
419
// over to a lane not using the primary airspeed sensor, so AHRS should know which airspeed sensor
420
// to use, i.e, the one being used by the primary lane. A lane switch could have happened due to an
421
// airspeed sensor fault, which makes this even more necessary
422
uint8_t get_active_airspeed_index() const;
423
424
// return the index of the primary core or -1 if no primary core selected
425
int8_t get_primary_core_index() const { return state.primary_core; }
426
427
// get the index of the current primary accelerometer sensor
428
uint8_t get_primary_accel_index(void) const { return state.primary_accel; }
429
430
// get the index of the current primary gyro sensor
431
uint8_t get_primary_gyro_index(void) const { return state.primary_gyro; }
432
433
// see if EKF lane switching is possible to avoid EKF failsafe
434
void check_lane_switch(void);
435
436
// request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe
437
void request_yaw_reset(void);
438
439
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
440
void set_posvelyaw_source_set(AP_NavEKF_Source::SourceSetSelection source_set_idx);
441
442
//returns index of active source set used, 0=primary, 1=secondary, 2=tertiary
443
uint8_t get_posvelyaw_source_set() const;
444
445
void Log_Write();
446
447
// check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed
448
bool using_noncompass_for_yaw(void) const;
449
450
// check if external nav is providing yaw
451
bool using_extnav_for_yaw(void) const;
452
453
// check if GPS is being used to estimate position or velocity
454
// always returns true for External and SIM EKF types
455
bool using_gps(void) const;
456
457
// set and save the ALT_M_NSE parameter value
458
void set_alt_measurement_noise(float noise);
459
460
enum class EKFType : uint8_t {
461
#if AP_AHRS_DCM_ENABLED
462
DCM = 0,
463
#endif
464
#if HAL_NAVEKF3_AVAILABLE
465
THREE = 3,
466
#endif
467
#if HAL_NAVEKF2_AVAILABLE
468
TWO = 2,
469
#endif
470
#if AP_AHRS_SIM_ENABLED
471
SIM = 10,
472
#endif
473
#if AP_AHRS_EXTERNAL_ENABLED
474
EXTERNAL = 11,
475
#endif
476
};
477
478
// returns a canonicalised and valid EKFType, as opposed to the raw
479
// parameter value which may be any value the user has set
480
EKFType configured_ekf_type(void) const;
481
482
// set the selected ekf type, for RC aux control
483
void set_ekf_type(EKFType ahrs_type) {
484
_ekf_type.set(ahrs_type);
485
}
486
487
// these are only out here so vehicles can reference them for parameters
488
#if HAL_NAVEKF2_AVAILABLE
489
NavEKF2 EKF2;
490
#endif
491
#if HAL_NAVEKF3_AVAILABLE
492
NavEKF3 EKF3;
493
#endif
494
495
// for holding parameters
496
static const struct AP_Param::GroupInfo var_info[];
497
498
// create a view
499
AP_AHRS_View *create_view(enum Rotation rotation, float pitch_trim_deg=0);
500
501
// write AOA and SSA information to dataflash logs:
502
void Write_AOA_SSA(void) const;
503
504
// return AOA
505
float getAOA(void) const { return _AOA; }
506
507
// return SSA
508
float getSSA(void) const { return _SSA; }
509
510
/*
511
* trim-related functions
512
*/
513
514
// get trim
515
const Vector3f &get_trim() const { return _trim.get(); }
516
517
// set trim
518
void set_trim(const Vector3f &new_trim);
519
520
// add_trim - adjust the roll and pitch trim up to a total of 10 degrees
521
void add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom = true);
522
523
// trim rotation matrices:
524
const Matrix3f& get_rotation_autopilot_body_to_vehicle_body(void) const { return _rotation_autopilot_body_to_vehicle_body; }
525
const Matrix3f& get_rotation_vehicle_body_to_autopilot_body(void) const { return _rotation_vehicle_body_to_autopilot_body; }
526
527
// Logging functions
528
void Log_Write_Home_And_Origin();
529
void Write_Attitude(const Vector3f &targets) const;
530
531
enum class LogOriginType {
532
ekf_origin = 0,
533
ahrs_home = 1
534
};
535
void Write_Origin(LogOriginType origin_type, const Location &loc) const;
536
void write_video_stabilisation() const;
537
538
// return a smoothed and corrected gyro vector in radians/second
539
// using the latest ins data (which may not have been consumed by
540
// the EKF yet)
541
Vector3f get_gyro_latest(void) const;
542
543
// get yaw rate in earth frame in radians/sec
544
float get_yaw_rate_earth(void) const {
545
return get_gyro() * get_rotation_body_to_ned().c;
546
}
547
548
/*
549
* home-related functionality
550
*/
551
552
// get the home location. This is const to prevent any changes to
553
// home without telling AHRS about the change
554
const Location &get_home(void) const {
555
return _home;
556
}
557
558
// functions to handle locking of home. Some vehicles use this to
559
// allow GCS to lock in a home location.
560
void lock_home() {
561
_home_locked = true;
562
}
563
bool home_is_locked() const {
564
return _home_locked;
565
}
566
567
// returns true if home is set
568
bool home_is_set(void) const {
569
return _home_is_set;
570
}
571
572
// set the home location in 10e7 degrees. This should be called
573
// when the vehicle is at this position. It is assumed that the
574
// current barometer and GPS altitudes correspond to this altitude
575
bool set_home(const Location &loc) WARN_IF_UNUSED;
576
577
/*
578
* Attitude-related public methods and attributes:
579
*/
580
581
#if AP_SCRIPTING_ENABLED
582
// deprecated functions for accessing rpy. Do not use, these will
583
// be removed.
584
float get_roll() const { return roll; }
585
float get_pitch() const { return pitch; }
586
float get_yaw() const { return yaw; }
587
#endif // AP_SCRIPTING_ENABLED
588
589
// roll/pitch/yaw euler angles, all in radians
590
float get_roll_rad() const { return roll; }
591
float get_pitch_rad() const { return pitch; }
592
float get_yaw_rad() const { return yaw; }
593
594
// roll/pitch/yaw euler angles, all in degrees
595
float get_roll_deg() const { return rpy_deg[0]; }
596
float get_pitch_deg() const { return rpy_deg[1]; }
597
float get_yaw_deg() const { return rpy_deg[2]; }
598
599
// helper trig value accessors
600
float cos_roll() const {
601
return _cos_roll;
602
}
603
float cos_pitch() const {
604
return _cos_pitch;
605
}
606
float cos_yaw() const {
607
return _cos_yaw;
608
}
609
float sin_roll() const {
610
return _sin_roll;
611
}
612
float sin_pitch() const {
613
return _sin_pitch;
614
}
615
float sin_yaw() const {
616
return _sin_yaw;
617
}
618
619
// floating point Euler angles (Degrees)
620
float rpy_deg[3];
621
622
// integer Euler angles (Degrees * 100)
623
int32_t roll_sensor;
624
int32_t pitch_sensor;
625
int32_t yaw_sensor;
626
627
const Matrix3f &get_rotation_body_to_ned(void) const { return state.dcm_matrix; }
628
629
// return a Quaternion representing our current attitude in NED frame
630
void get_quat_body_to_ned(Quaternion &quat) const;
631
632
#if AP_AHRS_DCM_ENABLED
633
// get rotation matrix specifically from DCM backend (used for
634
// compass calibrator)
635
const Matrix3f &get_DCM_rotation_body_to_ned(void) const {
636
return dcm_estimates.dcm_matrix;
637
}
638
#endif
639
640
// rotate a 2D vector from earth frame to body frame
641
// in result, x is forward, y is right
642
Vector2f earth_to_body2D(const Vector2f &ef_vector) const;
643
644
// rotate a 2D vector from earth frame to body frame
645
// in input, x is forward, y is right
646
Vector2f body_to_earth2D(const Vector2f &bf) const WARN_IF_UNUSED;
647
Vector2p body_to_earth2D_p(const Vector2p &bf) const WARN_IF_UNUSED;
648
649
// convert a vector from body to earth frame
650
Vector3f body_to_earth(const Vector3f &v) const;
651
652
// convert a vector from earth to body frame
653
Vector3f earth_to_body(const Vector3f &v) const;
654
655
/*
656
* methods for the benefit of LUA bindings
657
*/
658
// return current vibration vector for primary IMU
659
Vector3f get_vibration(void) const;
660
661
// return primary accels
662
const Vector3f &get_accel(void) const {
663
return AP::ins().get_accel(_get_primary_accel_index());
664
}
665
666
// return primary accel bias. This should be subtracted from
667
// get_accel() vector to get best current body frame accel
668
// estimate
669
const Vector3f &get_accel_bias(void) const {
670
return state.accel_bias;
671
}
672
673
/*
674
* AHRS is used as a transport for vehicle-takeoff-expected and
675
* vehicle-landing-expected:
676
*/
677
void set_takeoff_expected(bool b);
678
679
bool get_takeoff_expected(void) const {
680
return takeoff_expected;
681
}
682
683
void set_touchdown_expected(bool b);
684
685
bool get_touchdown_expected(void) const {
686
return touchdown_expected;
687
}
688
689
/*
690
* fly_forward is set by the vehicles to indicate the vehicle
691
* should generally be moving in the direction of its heading.
692
* It is an additional piece of information that the backends can
693
* use to provide additional and/or improved estimates.
694
*/
695
void set_fly_forward(bool b) {
696
fly_forward = b;
697
}
698
bool get_fly_forward(void) const {
699
return fly_forward;
700
}
701
702
/* we modify our behaviour based on what sort of vehicle the
703
* vehicle code tells us we are. This information is also pulled
704
* from AP_AHRS by other libraries
705
*/
706
enum class VehicleClass : uint8_t {
707
UNKNOWN,
708
GROUND,
709
COPTER,
710
FIXED_WING,
711
SUBMARINE,
712
};
713
VehicleClass get_vehicle_class(void) const {
714
return _vehicle_class;
715
}
716
void set_vehicle_class(VehicleClass vclass) {
717
_vehicle_class = vclass;
718
}
719
720
// get the view
721
AP_AHRS_View *get_view(void) const { return _view; };
722
723
// get access to an EKFGSF_yaw estimator
724
const EKFGSF_yaw *get_yaw_estimator(void) const;
725
726
private:
727
728
// roll/pitch/yaw euler angles, all in radians
729
float roll;
730
float pitch;
731
float yaw;
732
733
// optional view class
734
AP_AHRS_View *_view;
735
736
static AP_AHRS *_singleton;
737
738
/* we modify our behaviour based on what sort of vehicle the
739
* vehicle code tells us we are. This information is also pulled
740
* from AP_AHRS by other libraries
741
*/
742
VehicleClass _vehicle_class{VehicleClass::UNKNOWN};
743
744
// multi-thread access support
745
HAL_Semaphore _rsem;
746
747
/*
748
* Parameters
749
*/
750
AP_Int8 _wind_max;
751
AP_Int8 _board_orientation;
752
AP_Enum<EKFType> _ekf_type;
753
754
/*
755
* DCM-backend parameters; it takes references to these
756
*/
757
// settable parameters
758
AP_Float _kp_yaw;
759
AP_Float _kp;
760
AP_Float gps_gain;
761
762
AP_Float beta;
763
764
AP_Enum<GPSUse> _gps_use;
765
AP_Int8 _gps_minsats;
766
AP_Float _origin_lat;
767
AP_Float _origin_lon;
768
AP_Float _origin_alt;
769
770
EKFType active_EKF_type(void) const { return state.active_EKF; }
771
772
bool always_use_EKF() const {
773
return _ekf_flags & FLAG_ALWAYS_USE_EKF;
774
}
775
776
// check all cores providing consistent attitudes for prearm checks
777
bool attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const;
778
// convenience method for setting error string:
779
void set_failure_inconsistent_message(const char *estimator, const char *axis, float diff_rad, char *failure_msg, const uint8_t failure_msg_len) const;
780
781
/*
782
* Attitude-related private methods and attributes:
783
*/
784
// calculate sin/cos of roll/pitch/yaw from rotation
785
void calc_trig(const Matrix3f &rot,
786
float &cr, float &cp, float &cy,
787
float &sr, float &sp, float &sy) const;
788
789
// update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude
790
// should be called after _dcm_matrix is updated
791
void update_trig(void);
792
793
// update roll_sensor, pitch_sensor and yaw_sensor
794
void update_cd_values(void);
795
796
// helper trig variables
797
float _cos_roll{1.0f};
798
float _cos_pitch{1.0f};
799
float _cos_yaw{1.0f};
800
float _sin_roll;
801
float _sin_pitch;
802
float _sin_yaw;
803
804
#if HAL_NAVEKF2_AVAILABLE
805
void update_EKF2(void);
806
bool _ekf2_started;
807
#endif
808
#if HAL_NAVEKF3_AVAILABLE
809
bool _ekf3_started;
810
void update_EKF3(void);
811
#endif
812
813
const uint16_t startup_delay_ms = 1000;
814
uint32_t start_time_ms;
815
uint8_t _ekf_flags; // bitmask from Flags enumeration
816
817
void update_DCM();
818
819
/*
820
* home-related state
821
*/
822
void load_watchdog_home();
823
bool _checked_watchdog_home;
824
Location _home;
825
bool _home_is_set :1;
826
bool _home_locked :1;
827
828
// avoid setting current state repeatedly across all cores on all EKFs:
829
enum class TriState {
830
False = 0,
831
True = 1,
832
UNKNOWN = 3,
833
};
834
835
TriState terrainHgtStableState = TriState::UNKNOWN;
836
837
/*
838
* private AOA and SSA-related state and methods
839
*/
840
float _AOA, _SSA;
841
uint32_t _last_AOA_update_ms;
842
void update_AOA_SSA(void);
843
844
EKFType last_active_ekf_type;
845
846
#if AP_AHRS_SIM_ENABLED
847
void update_SITL(void);
848
#endif
849
850
#if AP_AHRS_EXTERNAL_ENABLED
851
void update_external(void);
852
#endif
853
854
/*
855
* trim-related state and private methods:
856
*/
857
858
// a vector to capture the difference between the controller and body frames
859
AP_Vector3f _trim;
860
861
// cached trim rotations
862
Vector3f _last_trim;
863
864
Matrix3f _rotation_autopilot_body_to_vehicle_body;
865
Matrix3f _rotation_vehicle_body_to_autopilot_body;
866
867
// last time orientation was updated from AHRS_ORIENTATION:
868
uint32_t last_orientation_update_ms;
869
870
// updates matrices responsible for rotating vectors from vehicle body
871
// frame to autopilot body frame from _trim variables
872
void update_trim_rotation_matrices();
873
874
/*
875
* AHRS is used as a transport for vehicle-takeoff-expected and
876
* vehicle-landing-expected:
877
*/
878
// update takeoff/touchdown flags
879
void update_flags();
880
bool takeoff_expected; // true if the vehicle is in a state that takeoff might be expected. Ground effect may be in play.
881
uint32_t takeoff_expected_start_ms;
882
bool touchdown_expected; // true if the vehicle is in a state that touchdown might be expected. Ground effect may be in play.
883
uint32_t touchdown_expected_start_ms;
884
885
/*
886
* wind estimation support
887
*/
888
bool wind_estimation_enabled;
889
890
/*
891
* fly_forward is set by the vehicles to indicate the vehicle
892
* should generally be moving in the direction of its heading.
893
* It is an additional piece of information that the backends can
894
* use to provide additional and/or improved estimates.
895
*/
896
bool fly_forward; // true if we can assume the vehicle will be flying forward on its X axis
897
898
// poke AP_Notify based on values from status
899
void update_notify_from_filter_status(const nav_filter_status &status);
900
901
/*
902
* copy results from a backend over AP_AHRS canonical results.
903
* This updates member variables like roll and pitch, as well as
904
* updating derived values like sin_roll and sin_pitch.
905
*/
906
void copy_estimates_from_backend_estimates(const AP_AHRS_Backend::Estimates &results);
907
908
// write out secondary estimates:
909
void Write_AHRS2(void) const;
910
// write POS (canonical vehicle position) message out:
911
void Write_POS(void) const;
912
913
// return an airspeed estimate if available. return true
914
// if we have an estimate
915
bool _airspeed_EAS(float &airspeed_ret, AirspeedEstimateType &status) const;
916
917
// return secondary attitude solution if available, as eulers in radians
918
bool _get_secondary_attitude(Vector3f &eulers) const;
919
920
// return secondary attitude solution if available, as quaternion
921
bool _get_secondary_quaternion(Quaternion &quat) const;
922
923
// get ground speed 2D
924
Vector2f _groundspeed_vector(void);
925
926
// get active EKF type
927
EKFType _active_EKF_type(void) const;
928
929
// return a wind estimation vector, in m/s
930
bool _wind_estimate(Vector3f &wind) const WARN_IF_UNUSED;
931
932
// return a true airspeed estimate (navigation airspeed) if
933
// available. return true if we have an estimate
934
bool _airspeed_TAS(float &airspeed_ret) const;
935
936
// return estimate of true airspeed vector in body frame in m/s
937
// returns false if estimate is unavailable
938
bool _airspeed_TAS(Vector3f &vec) const;
939
940
// return the quaternion defining the rotation from NED to XYZ (body) axes
941
bool _get_quaternion(Quaternion &quat) const WARN_IF_UNUSED;
942
943
// return the quaternion defining the rotation from NED to XYZ
944
// (body) axes for the passed-in type
945
bool _get_quaternion_for_ekf_type(Quaternion &quat, EKFType type) const;
946
947
// return secondary position solution if available
948
bool _get_secondary_position(Location &loc) const;
949
950
// return ground speed estimate in meters/second. Used by ground vehicles.
951
float _groundspeed(void);
952
953
// Retrieves the corrected NED delta velocity in use by the inertial navigation
954
void _getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const;
955
956
// returns the inertial navigation origin in lat/lon/alt
957
bool _get_origin(Location &ret) const WARN_IF_UNUSED;
958
959
// return origin for a specified EKF type
960
bool _get_origin(EKFType type, Location &ret) const;
961
962
// return a ground velocity in meters/second, North/East/Down
963
// order. Must only be called if have_inertial_nav() is true
964
bool _get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED;
965
966
// get secondary EKF type. returns false if no secondary (i.e. only using DCM)
967
bool _get_secondary_EKF_type(EKFType &secondary_ekf_type) const;
968
969
// return the index of the primary core or -1 if no primary core selected
970
int8_t _get_primary_core_index() const;
971
972
// get the index of the current primary accelerometer sensor
973
uint8_t _get_primary_accel_index(void) const;
974
975
// get the index of the current primary gyro sensor
976
uint8_t _get_primary_gyro_index(void) const;
977
978
// get the index of the current primary IMU
979
uint8_t _get_primary_IMU_index(void) const;
980
981
// get current location estimate
982
bool _get_location(Location &loc) const;
983
984
// return true if a airspeed sensor should be used for the AHRS airspeed estimate
985
bool _should_use_airspeed_sensor(uint8_t airspeed_index) const;
986
987
/*
988
update state structure
989
*/
990
void update_state(void);
991
992
// returns an EKF type to be used as active if we decide the
993
// primary is not good enough.
994
EKFType fallback_active_EKF_type(void) const;
995
996
// Record the current valid origin to parameters
997
// This may save the user from having to set the origin manually when using position controlled modes without GPS
998
void record_origin();
999
1000
/*
1001
state updated at the end of each update() call
1002
*/
1003
struct {
1004
EKFType active_EKF;
1005
uint8_t primary_IMU;
1006
uint8_t primary_gyro;
1007
uint8_t primary_accel;
1008
uint8_t primary_core;
1009
Vector3f gyro_estimate;
1010
Matrix3f dcm_matrix;
1011
Vector3f gyro_drift;
1012
Vector3f accel_ef;
1013
Vector3f accel_bias;
1014
Vector3f wind_estimate;
1015
bool wind_estimate_ok;
1016
float EAS2TAS;
1017
bool airspeed_EAS_ok;
1018
float airspeed_EAS;
1019
AirspeedEstimateType airspeed_estimate_type;
1020
bool airspeed_TAS_ok;
1021
float airspeed_TAS;
1022
Vector3f airspeed_TAS_vec;
1023
bool airspeed_TAS_vec_ok;
1024
Quaternion quat;
1025
bool quat_ok;
1026
Vector3f secondary_attitude;
1027
bool secondary_attitude_ok;
1028
Quaternion secondary_quat;
1029
bool secondary_quat_ok;
1030
Location location;
1031
bool location_ok;
1032
Location secondary_pos;
1033
bool secondary_pos_ok;
1034
Vector2f ground_speed_vec;
1035
float ground_speed;
1036
Vector3f corrected_dv;
1037
float corrected_dv_dt;
1038
Location origin;
1039
bool origin_ok;
1040
Vector3f velocity_NED;
1041
bool velocity_NED_ok;
1042
} state;
1043
1044
/*
1045
* backends (and their results)
1046
*/
1047
#if AP_AHRS_DCM_ENABLED
1048
AP_AHRS_DCM dcm{_kp_yaw, _kp, gps_gain, beta, _gps_use, _gps_minsats};
1049
struct AP_AHRS_Backend::Estimates dcm_estimates;
1050
#endif
1051
#if AP_AHRS_SIM_ENABLED
1052
#if HAL_NAVEKF3_AVAILABLE
1053
AP_AHRS_SIM sim{EKF3};
1054
#else
1055
AP_AHRS_SIM sim;
1056
#endif
1057
struct AP_AHRS_Backend::Estimates sim_estimates;
1058
#endif
1059
1060
#if AP_AHRS_EXTERNAL_ENABLED
1061
AP_AHRS_External external;
1062
struct AP_AHRS_Backend::Estimates external_estimates;
1063
#endif
1064
1065
enum class Options : uint16_t {
1066
DISABLE_DCM_FALLBACK_FW=(1U<<0),
1067
DISABLE_DCM_FALLBACK_VTOL=(1U<<1),
1068
DISABLE_AIRSPEED_EKF_CHECK=(1U<<2),
1069
RECORD_ORIGIN=(1U<<3),
1070
USE_RECORDED_ORIGIN_FOR_NONGPS=(1U<<4),
1071
};
1072
AP_Int16 _options;
1073
1074
bool option_set(Options option) const {
1075
return (_options & uint16_t(option)) != 0;
1076
}
1077
1078
// true when we have completed the common origin setup
1079
bool done_common_origin;
1080
};
1081
1082
namespace AP {
1083
AP_AHRS &ahrs();
1084
};
1085
1086