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