APM:Libraries
AP_AHRS.h
Go to the documentation of this file.
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_Compass/AP_Compass.h>
27 #include <AP_Beacon/AP_Beacon.h>
28 #include <AP_GPS/AP_GPS.h>
30 #include <AP_Baro/AP_Baro.h>
31 #include <AP_Param/AP_Param.h>
32 
33 class OpticalFlow;
34 #define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees
35 #define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter
36 #define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter
37 
38 enum AHRS_VehicleClass : uint8_t {
44 };
45 
46 
47 // forward declare view class
48 class AP_AHRS_View;
49 
50 class AP_AHRS
51 {
52 public:
53  friend class AP_AHRS_View;
54 
55  // Constructor
56  AP_AHRS() :
58  _cos_roll(1.0f),
59  _cos_pitch(1.0f),
60  _cos_yaw(1.0f)
61  {
62  _singleton = this;
63 
64  // load default values from var_info table
66 
67  // base the ki values by the sensors maximum drift
68  // rate.
70 
71  // enable centrifugal correction by default
73 
74  _last_trim = _trim.get();
77  }
78 
79  // empty virtual destructor
80  virtual ~AP_AHRS() {}
81 
82  // get singleton instance
83  static AP_AHRS *get_singleton() {
84  return _singleton;
85  }
86 
87  // init sets up INS board orientation
88  virtual void init() {
90  };
91 
92  // Accessors
93  void set_fly_forward(bool b) {
94  _flags.fly_forward = b;
95  }
96 
97  bool get_fly_forward(void) const {
98  return _flags.fly_forward;
99  }
100 
101  /*
102  set the "likely flying" flag. This is not guaranteed to be
103  accurate, but is the vehicle codes best guess as to the whether
104  the vehicle is currently flying
105  */
106  void set_likely_flying(bool b) {
107  if (b && !_flags.likely_flying) {
109  }
110  _flags.likely_flying = b;
111  }
112 
113  /*
114  get the likely flying status. Returns true if the vehicle code
115  thinks we are flying at the moment. Not guaranteed to be
116  accurate
117  */
118  bool get_likely_flying(void) const {
119  return _flags.likely_flying;
120  }
121 
122  /*
123  return time in milliseconds since likely_flying was set
124  true. Returns zero if likely_flying is currently false
125  */
126  uint32_t get_time_flying_ms(void) const {
127  if (!_flags.likely_flying) {
128  return 0;
129  }
130  return AP_HAL::millis() - _last_flying_ms;
131  }
132 
134  return _vehicle_class;
135  }
136 
138  _vehicle_class = vclass;
139  }
140 
141  void set_wind_estimation(bool b) {
143  }
144 
146  _compass = compass;
147  set_orientation();
148  }
149 
150  const Compass* get_compass() const {
151  return _compass;
152  }
153 
155  _optflow = optflow;
156  }
157 
158  const OpticalFlow* get_optflow() const {
159  return _optflow;
160  }
161 
162  // allow for runtime change of orientation
163  // this makes initial config easier
164  void set_orientation();
165 
168  }
169 
171  _beacon = beacon;
172  }
173 
174  const AP_Airspeed *get_airspeed(void) const {
175  return _airspeed;
176  }
177 
178  const AP_Beacon *get_beacon(void) const {
179  return _beacon;
180  }
181 
182  // get the index of the current primary accelerometer sensor
183  virtual uint8_t get_primary_accel_index(void) const {
184  return AP::ins().get_primary_accel();
185  }
186 
187  // get the index of the current primary gyro sensor
188  virtual uint8_t get_primary_gyro_index(void) const {
189  return AP::ins().get_primary_gyro();
190  }
191 
192  // accelerometer values in the earth frame in m/s/s
193  virtual const Vector3f &get_accel_ef(uint8_t i) const {
194  return _accel_ef[i];
195  }
196  virtual const Vector3f &get_accel_ef(void) const {
197  return get_accel_ef(AP::ins().get_primary_accel());
198  }
199 
200  // blended accelerometer values in the earth frame in m/s/s
201  virtual const Vector3f &get_accel_ef_blended(void) const {
202  return _accel_ef_blended;
203  }
204 
205  // get yaw rate in earth frame in radians/sec
206  float get_yaw_rate_earth(void) const {
207  return get_gyro() * get_rotation_body_to_ned().c;
208  }
209 
210  // Methods
211  virtual void update(bool skip_ins_update=false) = 0;
212 
213  // report any reason for why the backend is refusing to initialise
214  virtual const char *prearm_failure_reason(void) const {
215  return nullptr;
216  }
217 
218  // is the EKF backend doing its own sensor logging?
219  virtual bool have_ekf_logging(void) const {
220  return false;
221  }
222 
223  // Euler angles (radians)
224  float roll;
225  float pitch;
226  float yaw;
227 
228  // integer Euler angles (Degrees * 100)
229  int32_t roll_sensor;
230  int32_t pitch_sensor;
231  int32_t yaw_sensor;
232 
233  // return a smoothed and corrected gyro vector
234  virtual const Vector3f &get_gyro(void) const = 0;
235 
236  // return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)
237  Vector3f get_gyro_latest(void) const;
238 
239  // return the current estimate of the gyro drift
240  virtual const Vector3f &get_gyro_drift(void) const = 0;
241 
242  // reset the current gyro drift estimate
243  // should be called if gyro offsets are recalculated
244  virtual void reset_gyro_drift(void) = 0;
245 
246  // reset the current attitude, used on new IMU calibration
247  virtual void reset(bool recover_eulers=false) = 0;
248 
249  // reset the current attitude, used on new IMU calibration
250  virtual void reset_attitude(const float &roll, const float &pitch, const float &yaw) = 0;
251 
252  // return the average size of the roll/pitch error estimate
253  // since last call
254  virtual float get_error_rp(void) const = 0;
255 
256  // return the average size of the yaw error estimate
257  // since last call
258  virtual float get_error_yaw(void) const = 0;
259 
260  // return a DCM rotation matrix representing our current
261  // attitude
262  virtual const Matrix3f &get_rotation_body_to_ned(void) const = 0;
265 
266  // get our current position estimate. Return true if a position is available,
267  // otherwise false. This call fills in lat, lng and alt
268  virtual bool get_position(struct Location &loc) const = 0;
269 
270  virtual bool get_hagl(float &height) const { return false; }
271 
272  // return a wind estimation vector, in m/s
273  virtual Vector3f wind_estimate(void) const = 0;
274 
275  // return an airspeed estimate if available. return true
276  // if we have an estimate
277  virtual bool airspeed_estimate(float *airspeed_ret) const;
278 
279  // return a true airspeed estimate (navigation airspeed) if
280  // available. return true if we have an estimate
281  bool airspeed_estimate_true(float *airspeed_ret) const {
282  if (!airspeed_estimate(airspeed_ret)) {
283  return false;
284  }
285  *airspeed_ret *= get_EAS2TAS();
286  return true;
287  }
288 
289  // get apparent to true airspeed ratio
290  float get_EAS2TAS(void) const {
291  if (_airspeed) {
292  return _airspeed->get_EAS2TAS();
293  }
294  return 1.0f;
295  }
296 
297  // return true if airspeed comes from an airspeed sensor, as
298  // opposed to an IMU estimate
299  bool airspeed_sensor_enabled(void) const {
300  return _airspeed != nullptr && _airspeed->use() && _airspeed->healthy();
301  }
302 
303  // return a ground vector estimate in meters/second, in North/East order
304  virtual Vector2f groundspeed_vector(void);
305 
306  // return a ground velocity in meters/second, North/East/Down
307  // order. This will only be accurate if have_inertial_nav() is
308  // true
309  virtual bool get_velocity_NED(Vector3f &vec) const {
310  return false;
311  }
312 
313  // returns the expected NED magnetic field
314  virtual bool get_expected_mag_field_NED(Vector3f &ret) const {
315  return false;
316  }
317 
318  // returns the estimated magnetic field offsets in body frame
319  virtual bool get_mag_field_correction(Vector3f &ret) const {
320  return false;
321  }
322 
323  // return a position relative to home in meters, North/East/Down
324  // order. This will only be accurate if have_inertial_nav() is
325  // true
326  virtual bool get_relative_position_NED_home(Vector3f &vec) const {
327  return false;
328  }
329 
330  // return a position relative to origin in meters, North/East/Down
331  // order. This will only be accurate if have_inertial_nav() is
332  // true
333  virtual bool get_relative_position_NED_origin(Vector3f &vec) const {
334  return false;
335  }
336  // return a position relative to home in meters, North/East
337  // order. Return true if estimate is valid
338  virtual bool get_relative_position_NE_home(Vector2f &vecNE) const {
339  return false;
340  }
341 
342  // return a position relative to origin in meters, North/East
343  // order. Return true if estimate is valid
344  virtual bool get_relative_position_NE_origin(Vector2f &vecNE) const {
345  return false;
346  }
347 
348  // return a Down position relative to home in meters
349  // if EKF is unavailable will return the baro altitude
350  virtual void get_relative_position_D_home(float &posD) const = 0;
351 
352  // return a Down position relative to origin in meters
353  // Return true if estimate is valid
354  virtual bool get_relative_position_D_origin(float &posD) const {
355  return false;
356  }
357 
358  // return ground speed estimate in meters/second. Used by ground vehicles.
359  float groundspeed(void) {
360  return groundspeed_vector().length();
361  }
362 
363  // return true if we will use compass for yaw
364  virtual bool use_compass(void) {
365  return _compass && _compass->use_for_yaw();
366  }
367 
368  // return true if yaw has been initialised
369  bool yaw_initialised(void) const {
370  return _flags.have_initial_yaw;
371  }
372 
373  // set the correct centrifugal flag
374  // allows arducopter to disable corrections when disarmed
375  void set_correct_centrifugal(bool setting) {
376  _flags.correct_centrifugal = setting;
377  }
378 
379  // get the correct centrifugal flag
380  bool get_correct_centrifugal(void) const {
382  }
383 
384  // get trim
385  const Vector3f &get_trim() const {
386  return _trim.get();
387  }
388 
389  // set trim
390  virtual void set_trim(Vector3f new_trim);
391 
392  // add_trim - adjust the roll and pitch trim up to a total of 10 degrees
393  virtual void add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom = true);
394 
395  // helper trig value accessors
396  float cos_roll() const {
397  return _cos_roll;
398  }
399  float cos_pitch() const {
400  return _cos_pitch;
401  }
402  float cos_yaw() const {
403  return _cos_yaw;
404  }
405  float sin_roll() const {
406  return _sin_roll;
407  }
408  float sin_pitch() const {
409  return _sin_pitch;
410  }
411  float sin_yaw() const {
412  return _sin_yaw;
413  }
414 
415  // for holding parameters
416  static const struct AP_Param::GroupInfo var_info[];
417 
418  // return secondary attitude solution if available, as eulers in radians
419  virtual bool get_secondary_attitude(Vector3f &eulers) const {
420  return false;
421  }
422 
423  // return secondary attitude solution if available, as quaternion
424  virtual bool get_secondary_quaternion(Quaternion &quat) const {
425  return false;
426  }
427 
428  // return secondary position solution if available
429  virtual bool get_secondary_position(struct Location &loc) const {
430  return false;
431  }
432 
433  // get the home location. This is const to prevent any changes to
434  // home without telling AHRS about the change
435  const struct Location &get_home(void) const {
436  return _home;
437  }
438 
439  // functions to handle locking of home. Some vehicles use this to
440  // allow GCS to lock in a home location.
441  void lock_home() {
442  _home_locked = true;
443  }
444  bool home_is_locked() const {
445  return _home_locked;
446  }
447 
448  // returns true if home is set
449  bool home_is_set(void) const {
450  return _home_is_set;
451  }
452 
453  // set the home location in 10e7 degrees. This should be called
454  // when the vehicle is at this position. It is assumed that the
455  // current barometer and GPS altitudes correspond to this altitude
456  virtual void set_home(const Location &loc) = 0;
457 
458  // set the EKF's origin location in 10e7 degrees. This should only
459  // be called when the EKF has no absolute position reference (i.e. GPS)
460  // from which to decide the origin on its own
461  virtual bool set_origin(const Location &loc) { return false; }
462 
463  // returns the inertial navigation origin in lat/lon/alt
464  virtual bool get_origin(Location &ret) const { return false; }
465 
467 
468  // return true if the AHRS object supports inertial navigation,
469  // with very accurate position and velocity
470  virtual bool have_inertial_nav(void) const {
471  return false;
472  }
473 
474  // return the active accelerometer instance
475  uint8_t get_active_accel_instance(void) const {
476  return _active_accel_instance;
477  }
478 
479  // is the AHRS subsystem healthy?
480  virtual bool healthy(void) const = 0;
481 
482  // true if the AHRS has completed initialisation
483  virtual bool initialised(void) const {
484  return true;
485  };
486 
487  // return the amount of yaw angle change due to the last yaw angle reset in radians
488  // returns the time of the last yaw angle reset or 0 if no reset has ever occurred
489  virtual uint32_t getLastYawResetAngle(float &yawAng) const {
490  return 0;
491  };
492 
493  // return the amount of NE position change in metres due to the last reset
494  // returns the time of the last reset or 0 if no reset has ever occurred
495  virtual uint32_t getLastPosNorthEastReset(Vector2f &pos) const {
496  return 0;
497  };
498 
499  // return the amount of NE velocity change in metres/sec due to the last reset
500  // returns the time of the last reset or 0 if no reset has ever occurred
501  virtual uint32_t getLastVelNorthEastReset(Vector2f &vel) const {
502  return 0;
503  };
504 
505  // return the amount of vertical position change due to the last reset in meters
506  // returns the time of the last reset or 0 if no reset has ever occurred
507  virtual uint32_t getLastPosDownReset(float &posDelta) const {
508  return 0;
509  };
510 
511  // Resets the baro so that it reads zero at the current height
512  // Resets the EKF height to zero
513  // Adjusts the EKf origin height so that the EKF height + origin height is the same as before
514  // Returns true if the height datum reset has been performed
515  // If using a range finder for height no reset is performed and it returns false
516  virtual bool resetHeightDatum(void) {
517  return false;
518  }
519 
520  // get_variances - provides the innovations normalised using the innovation variance where a value of 0
521  // indicates perfect consistency between the measurement and the EKF solution and a value of of 1 is the maximum
522  // inconsistency that will be accepted by the filter
523  // boolean false is returned if variances are not available
524  virtual bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const {
525  return false;
526  }
527 
528  // time that the AHRS has been up
529  virtual uint32_t uptime_ms(void) const = 0;
530 
531  // get the selected ekf type, for allocation decisions
532  int8_t get_ekf_type(void) const {
533  return _ekf_type;
534  }
535 
536  // Retrieves the corrected NED delta velocity in use by the inertial navigation
537  virtual void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const {
538  ret.zero();
539  const AP_InertialSensor &_ins = AP::ins();
540  _ins.get_delta_velocity(ret);
541  dt = _ins.get_delta_velocity_dt();
542  }
543 
544  // create a view
545  AP_AHRS_View *create_view(enum Rotation rotation);
546 
547  // return calculated AOA
548  float getAOA(void);
549 
550  // return calculated SSA
551  float getSSA(void);
552 
553  // rotate a 2D vector from earth frame to body frame
554  // in result, x is forward, y is right
555  Vector2f rotate_earth_to_body2D(const Vector2f &ef_vector) const;
556 
557  // rotate a 2D vector from earth frame to body frame
558  // in input, x is forward, y is right
559  Vector2f rotate_body_to_earth2D(const Vector2f &bf) const;
560 
561  virtual void update_AOA_SSA(void);
562 
563  // get_hgt_ctrl_limit - get maximum height to be observed by the
564  // control loops in meters and a validity flag. It will return
565  // false when no limiting is required
566  virtual bool get_hgt_ctrl_limit(float &limit) const { return false; };
567 
568  // Write position and quaternion data from an external navigation system
569  virtual void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms) { }
570 
571 protected:
573 
574  // settable parameters
575  // these are public for ArduCopter
576  AP_Float _kp_yaw;
577  AP_Float _kp;
578  AP_Float gps_gain;
579 
580  AP_Float beta;
581  AP_Int8 _gps_use;
582  AP_Int8 _wind_max;
584  AP_Int8 _gps_minsats;
585  AP_Int8 _gps_delay;
586  AP_Int8 _ekf_type;
587  AP_Float _custom_roll;
588  AP_Float _custom_pitch;
589  AP_Float _custom_yaw;
590 
592 
593  // flags structure
594  struct ahrs_flags {
595  uint8_t have_initial_yaw : 1; // whether the yaw value has been intialised with a reference
596  uint8_t fly_forward : 1; // 1 if we can assume the aircraft will be flying forward on its X axis
597  uint8_t correct_centrifugal : 1; // 1 if we should correct for centrifugal forces (allows arducopter to turn this off when motors are disarmed)
598  uint8_t wind_estimation : 1; // 1 if we should do wind estimation
599  uint8_t likely_flying : 1; // 1 if vehicle is probably flying
600  } _flags;
601 
602  // time when likely_flying last went true
603  uint32_t _last_flying_ms;
604 
605  // calculate sin/cos of roll/pitch/yaw from rotation
606  void calc_trig(const Matrix3f &rot,
607  float &cr, float &cp, float &cy,
608  float &sr, float &sp, float &sy) const;
609 
610  // update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude
611  // should be called after _dcm_matrix is updated
612  void update_trig(void);
613 
614  // update roll_sensor, pitch_sensor and yaw_sensor
615  void update_cd_values(void);
616 
617  // pointer to compass object, if available
619 
620  // pointer to OpticalFlow object, if available
622 
623  // pointer to airspeed object, if available
625 
626  // pointer to beacon object, if available
628 
629  // time in microseconds of last compass update
631 
632  // a vector to capture the difference between the controller and body frames
633  AP_Vector3f _trim;
634 
635  // cached trim rotations
639 
640  // the limit of the gyro drift claimed by the sensors, in
641  // radians/s/s
643 
644  // accelerometer values in the earth frame in m/s/s
647 
648  // Declare filter states for HPF and LPF used by complementary
649  // filter in AP_AHRS::groundspeed_vector
650  Vector2f _lp; // ground vector low-pass filter
651  Vector2f _hp; // ground vector high-pass filter
652  Vector2f _lastGndVelADS; // previous HPF input
653 
654  // reference position for NED positions
655  struct Location _home;
656  bool _home_is_set :1;
657  bool _home_locked :1;
658 
659  // helper trig variables
662 
663  // which accelerometer instance is active
665 
666  // optional view class
668 
669  // AOA and SSA
670  float _AOA, _SSA;
672 
673 private:
675 
676 };
677 
678 #include "AP_AHRS_DCM.h"
679 #include "AP_AHRS_NavEKF.h"
680 
681 #if AP_AHRS_NAVEKF_AVAILABLE
682 #define AP_AHRS_TYPE AP_AHRS_NavEKF
683 #else
684 #define AP_AHRS_TYPE AP_AHRS
685 #endif
686 
687 namespace AP {
688  AP_AHRS &ahrs();
689 };
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_AHRS.h:416
float cos_yaw() const
Definition: AP_AHRS.h:402
virtual uint32_t getLastPosNorthEastReset(Vector2f &pos) const
Definition: AP_AHRS.h:495
virtual bool get_hagl(float &height) const
Definition: AP_AHRS.h:270
bool yaw_initialised(void) const
Definition: AP_AHRS.h:369
virtual bool get_velocity_NED(Vector3f &vec) const
Definition: AP_AHRS.h:309
float roll
Definition: AP_AHRS.h:224
AP_Int8 _ekf_type
Definition: AP_AHRS.h:586
const Vector3f & get_trim() const
Definition: AP_AHRS.h:385
uint8_t have_initial_yaw
Definition: AP_AHRS.h:595
AP_Int8 _wind_max
Definition: AP_AHRS.h:582
void set_compass(Compass *compass)
Definition: AP_AHRS.h:145
bool airspeed_estimate_true(float *airspeed_ret) const
Definition: AP_AHRS.h:281
virtual uint32_t getLastPosDownReset(float &posDelta) const
Definition: AP_AHRS.h:507
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
float getAOA(void)
Definition: AP_AHRS.cpp:434
virtual void update(bool skip_ins_update=false)=0
bool _home_is_set
Definition: AP_AHRS.h:656
const OpticalFlow * _optflow
Definition: AP_AHRS.h:621
AP_Beacon beacon
virtual void getCorrectedDeltaVelocityNED(Vector3f &ret, float &dt) const
Definition: AP_AHRS.h:537
void set_airspeed(AP_Airspeed *airspeed)
Definition: AP_AHRS.h:166
float _sin_roll
Definition: AP_AHRS.h:661
virtual bool have_ekf_logging(void) const
Definition: AP_AHRS.h:219
virtual const Vector3f & get_accel_ef_blended(void) const
Definition: AP_AHRS.h:201
AP_Airspeed * _airspeed
Definition: AP_AHRS.h:624
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
virtual const Vector3f & get_gyro(void) const =0
float _AOA
Definition: AP_AHRS.h:670
float sin_yaw() const
Definition: AP_AHRS.h:411
virtual void reset_attitude(const float &roll, const float &pitch, const float &yaw)=0
AP_Float _kp
Definition: AP_AHRS.h:577
virtual bool get_position(struct Location &loc) const =0
virtual bool get_relative_position_NED_home(Vector3f &vec) const
Definition: AP_AHRS.h:326
AP_AHRS()
Definition: AP_AHRS.h:56
virtual Vector3f wind_estimate(void) const =0
AP_Int8 _board_orientation
Definition: AP_AHRS.h:583
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
AP_Int8 _gps_minsats
Definition: AP_AHRS.h:584
virtual void set_home(const Location &loc)=0
virtual uint32_t getLastVelNorthEastReset(Vector2f &vel) const
Definition: AP_AHRS.h:501
uint8_t get_primary_gyro(void) const
virtual bool get_relative_position_NED_origin(Vector3f &vec) const
Definition: AP_AHRS.h:333
AHRS_VehicleClass get_vehicle_class(void) const
Definition: AP_AHRS.h:133
virtual float get_error_yaw(void) const =0
virtual const char * prearm_failure_reason(void) const
Definition: AP_AHRS.h:214
AP_Float _kp_yaw
Definition: AP_AHRS.h:576
float pitch
Definition: AP_AHRS.h:225
virtual bool get_relative_position_NE_origin(Vector2f &vecNE) const
Definition: AP_AHRS.h:344
AHRS_VehicleClass _vehicle_class
Definition: AP_AHRS.h:572
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
virtual void reset_gyro_drift(void)=0
virtual void reset(bool recover_eulers=false)=0
Vector2f _lastGndVelADS
Definition: AP_AHRS.h:652
virtual bool airspeed_estimate(float *airspeed_ret) const
Definition: AP_AHRS.cpp:170
float yaw
Definition: AP_AHRS.h:226
float get_yaw_rate_earth(void) const
Definition: AP_AHRS.h:206
virtual bool get_secondary_quaternion(Quaternion &quat) const
Definition: AP_AHRS.h:424
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
virtual bool initialised(void) const
Definition: AP_AHRS.h:483
void Log_Write_Home_And_Origin()
Definition: AP_AHRS.cpp:462
Vector3f _accel_ef_blended
Definition: AP_AHRS.h:646
virtual ~AP_AHRS()
Definition: AP_AHRS.h:80
bool get_likely_flying(void) const
Definition: AP_AHRS.h:118
AP_Float gps_gain
Definition: AP_AHRS.h:578
void set_orientation()
Definition: AP_AHRS.cpp:217
virtual Vector2f groundspeed_vector(void)
Definition: AP_AHRS.cpp:235
virtual void update_AOA_SSA(void)
Definition: AP_AHRS.cpp:387
virtual const Matrix3f & get_rotation_body_to_ned(void) const =0
uint8_t correct_centrifugal
Definition: AP_AHRS.h:597
Rotation
Definition: rotations.h:27
static AP_AHRS * get_singleton()
Definition: AP_AHRS.h:83
AHRS_VehicleClass
Definition: AP_AHRS.h:38
AP_AHRS_View * create_view(enum Rotation rotation)
Definition: AP_AHRS.cpp:364
void set_likely_flying(bool b)
Definition: AP_AHRS.h:106
Vector2f rotate_earth_to_body2D(const Vector2f &ef_vector) const
Definition: AP_AHRS.cpp:448
virtual void add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom=true)
Definition: AP_AHRS.cpp:199
virtual void init()
Definition: AP_AHRS.h:88
int32_t roll_sensor
Definition: AP_AHRS.h:229
Matrix3f _rotation_vehicle_body_to_autopilot_body
Definition: AP_AHRS.h:638
void lock_home()
Definition: AP_AHRS.h:441
virtual bool have_inertial_nav(void) const
Definition: AP_AHRS.h:470
virtual const Vector3f & get_accel_ef(void) const
Definition: AP_AHRS.h:196
void set_wind_estimation(bool b)
Definition: AP_AHRS.h:141
Vector2f _lp
Definition: AP_AHRS.h:650
const Compass * get_compass() const
Definition: AP_AHRS.h:150
const AP_Airspeed * get_airspeed(void) const
Definition: AP_AHRS.h:174
A system for managing and storing variables that are of general interest to the system.
Matrix3< T > transposed(void) const
Definition: matrix3.cpp:189
uint8_t get_primary_accel(void) const
Vector3f _last_trim
Definition: AP_AHRS.h:636
Matrix3f _custom_rotation
Definition: AP_AHRS.h:591
float cos_roll() const
Definition: AP_AHRS.h:396
Vector2f _hp
Definition: AP_AHRS.h:651
virtual uint32_t uptime_ms(void) const =0
AP_Beacon * _beacon
Definition: AP_AHRS.h:627
virtual void set_trim(Vector3f new_trim)
Definition: AP_AHRS.cpp:190
Definition: AP_AHRS.cpp:486
void set_fly_forward(bool b)
Definition: AP_AHRS.h:93
float _sin_pitch
Definition: AP_AHRS.h:661
float _sin_yaw
Definition: AP_AHRS.h:661
float _gyro_drift_limit
Definition: AP_AHRS.h:642
int32_t pitch_sensor
Definition: AP_AHRS.h:230
virtual void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
Definition: AP_AHRS.h:569
void update_cd_values(void)
Definition: AP_AHRS.cpp:352
#define f(i)
int8_t get_ekf_type(void) const
Definition: AP_AHRS.h:532
virtual const Vector3f & get_accel_ef(uint8_t i) const
Definition: AP_AHRS.h:193
float getSSA(void)
Definition: AP_AHRS.cpp:441
static OpticalFlow optflow
T y
Definition: vector3.h:67
Vector3< T > c
Definition: matrix3.h:48
uint32_t millis()
Definition: system.cpp:157
void set_correct_centrifugal(bool setting)
Definition: AP_AHRS.h:375
Matrix3f _rotation_autopilot_body_to_vehicle_body
Definition: AP_AHRS.h:637
void set_vehicle_class(AHRS_VehicleClass vclass)
Definition: AP_AHRS.h:137
virtual bool get_relative_position_NE_home(Vector2f &vecNE) const
Definition: AP_AHRS.h:338
Vector2f rotate_body_to_earth2D(const Vector2f &bf) const
Definition: AP_AHRS.cpp:455
Vector3f get_gyro_latest(void) const
Definition: AP_AHRS.cpp:163
AP_Float _custom_roll
Definition: AP_AHRS.h:587
const Matrix3f & get_rotation_vehicle_body_to_autopilot_body(void) const
Definition: AP_AHRS.h:264
virtual const Vector3f & get_gyro_drift(void) const =0
AP_Float _custom_yaw
Definition: AP_AHRS.h:589
bool get_correct_centrifugal(void) const
Definition: AP_AHRS.h:380
bool _home_locked
Definition: AP_AHRS.h:657
void set_optflow(const OpticalFlow *optflow)
Definition: AP_AHRS.h:154
virtual float get_error_rp(void) const =0
static Compass compass
Definition: AHRS_Test.cpp:20
AP_Float beta
Definition: AP_AHRS.h:580
uint8_t get_active_accel_instance(void) const
Definition: AP_AHRS.h:475
float cos_pitch() const
Definition: AP_AHRS.h:399
uint8_t _active_accel_instance
Definition: AP_AHRS.h:664
AP_Int8 _gps_delay
Definition: AP_AHRS.h:585
struct Location _home
Definition: AP_AHRS.h:655
const Matrix3f & get_rotation_autopilot_body_to_vehicle_body(void) const
Definition: AP_AHRS.h:263
Vector3f _accel_ef[INS_MAX_INSTANCES]
Definition: AP_AHRS.h:645
AP_Int8 _gps_use
Definition: AP_AHRS.h:581
AP_Float _custom_pitch
Definition: AP_AHRS.h:588
float length(void) const
Definition: vector2.cpp:24
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
float _cos_roll
Definition: AP_AHRS.h:660
float get_EAS2TAS(uint8_t i) const
Definition: AP_Airspeed.h:123
uint8_t wind_estimation
Definition: AP_AHRS.h:598
bool home_is_locked() const
Definition: AP_AHRS.h:444
AP_AHRS_View * _view
Definition: AP_AHRS.h:667
float get_delta_velocity_dt(uint8_t i) const
const OpticalFlow * get_optflow() const
Definition: AP_AHRS.h:158
virtual bool get_hgt_ctrl_limit(float &limit) const
Definition: AP_AHRS.h:566
virtual uint8_t get_primary_accel_index(void) const
Definition: AP_AHRS.h:183
virtual bool healthy(void) const =0
virtual bool use_compass(void)
Definition: AP_AHRS.h:364
uint8_t fly_forward
Definition: AP_AHRS.h:596
bool get_fly_forward(void) const
Definition: AP_AHRS.h:97
virtual uint32_t getLastYawResetAngle(float &yawAng) const
Definition: AP_AHRS.h:489
void set_beacon(AP_Beacon *beacon)
Definition: AP_AHRS.h:170
virtual bool get_origin(Location &ret) const
Definition: AP_AHRS.h:464
uint32_t _compass_last_update
Definition: AP_AHRS.h:630
virtual bool get_secondary_attitude(Vector3f &eulers) const
Definition: AP_AHRS.h:419
Compass * _compass
Definition: AP_AHRS.h:618
virtual bool get_secondary_position(struct Location &loc) const
Definition: AP_AHRS.h:429
const AP_Beacon * get_beacon(void) const
Definition: AP_AHRS.h:178
uint32_t get_time_flying_ms(void) const
Definition: AP_AHRS.h:126
virtual uint8_t get_primary_gyro_index(void) const
Definition: AP_AHRS.h:188
float groundspeed(void)
Definition: AP_AHRS.h:359
virtual bool get_expected_mag_field_NED(Vector3f &ret) const
Definition: AP_AHRS.h:314
uint8_t likely_flying
Definition: AP_AHRS.h:599
AP_InertialSensor & ins()
float _SSA
Definition: AP_AHRS.h:670
struct AP_AHRS::ahrs_flags _flags
void calc_trig(const Matrix3f &rot, float &cr, float &cp, float &cy, float &sr, float &sp, float &sy) const
Definition: AP_AHRS.cpp:290
bool airspeed_sensor_enabled(void) const
Definition: AP_AHRS.h:299
float get_EAS2TAS(void) const
Definition: AP_AHRS.h:290
virtual bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
Definition: AP_AHRS.h:524
void update_trig(void)
Definition: AP_AHRS.cpp:336
AP_Vector3f _trim
Definition: AP_AHRS.h:633
#define INS_MAX_INSTANCES
float sin_roll() const
Definition: AP_AHRS.h:405
float sin_pitch() const
Definition: AP_AHRS.h:408
bool home_is_set(void) const
Definition: AP_AHRS.h:449
int32_t yaw_sensor
Definition: AP_AHRS.h:231
virtual bool get_mag_field_correction(Vector3f &ret) const
Definition: AP_AHRS.h:319
bool healthy(uint8_t i) const
Definition: AP_Airspeed.h:135
float _cos_yaw
Definition: AP_AHRS.h:660
float _cos_pitch
Definition: AP_AHRS.h:660
uint32_t _last_flying_ms
Definition: AP_AHRS.h:603
virtual void get_relative_position_D_home(float &posD) const =0
static AP_AHRS * _singleton
Definition: AP_AHRS.h:674
virtual bool get_relative_position_D_origin(float &posD) const
Definition: AP_AHRS.h:354
virtual bool set_origin(const Location &loc)
Definition: AP_AHRS.h:461
float get_gyro_drift_rate(void) const
void zero()
Definition: vector3.h:182
T x
Definition: vector3.h:67
uint32_t _last_AOA_update_ms
Definition: AP_AHRS.h:671
virtual bool resetHeightDatum(void)
Definition: AP_AHRS.h:516
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
AP_Int8 use
Definition: AP_Airspeed.h:181