APM:Libraries
AP_AHRS.cpp
Go to the documentation of this file.
1 /*
2  APM_AHRS.cpp
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 #include "AP_AHRS.h"
18 #include "AP_AHRS_View.h"
19 #include <AP_HAL/AP_HAL.h>
20 #include <DataFlash/DataFlash.h>
21 
22 extern const AP_HAL::HAL& hal;
23 
24 // table of user settable parameters
26  // index 0 and 1 are for old parameters that are no longer not used
27 
28  // @Param: GPS_GAIN
29  // @DisplayName: AHRS GPS gain
30  // @Description: This controls how much to use the GPS to correct the attitude. This should never be set to zero for a plane as it would result in the plane losing control in turns. For a plane please use the default value of 1.0.
31  // @Range: 0.0 1.0
32  // @Increment: .01
33  // @User: Advanced
34  AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS, gps_gain, 1.0f),
35 
36  // @Param: GPS_USE
37  // @DisplayName: AHRS use GPS for navigation
38  // @Description: This controls whether to use dead-reckoning or GPS based navigation. If set to 0 then the GPS won't be used for navigation, and only dead reckoning will be used. A value of zero should never be used for normal flight. Currently this affects only the DCM-based AHRS: the EKF uses GPS whenever it is available.
39  // @Values: 0:Disabled,1:Enabled
40  // @User: Advanced
41  AP_GROUPINFO("GPS_USE", 3, AP_AHRS, _gps_use, 1),
42 
43  // @Param: YAW_P
44  // @DisplayName: Yaw P
45  // @Description: This controls the weight the compass or GPS has on the heading. A higher value means the heading will track the yaw source (GPS or compass) more rapidly.
46  // @Range: 0.1 0.4
47  // @Increment: .01
48  // @User: Advanced
49  AP_GROUPINFO("YAW_P", 4, AP_AHRS, _kp_yaw, 0.2f),
50 
51  // @Param: RP_P
52  // @DisplayName: AHRS RP_P
53  // @Description: This controls how fast the accelerometers correct the attitude
54  // @Range: 0.1 0.4
55  // @Increment: .01
56  // @User: Advanced
57  AP_GROUPINFO("RP_P", 5, AP_AHRS, _kp, 0.2f),
58 
59  // @Param: WIND_MAX
60  // @DisplayName: Maximum wind
61  // @Description: This sets the maximum allowable difference between ground speed and airspeed. This allows the plane to cope with a failing airspeed sensor. A value of zero means to use the airspeed as is.
62  // @Range: 0 127
63  // @Units: m/s
64  // @Increment: 1
65  // @User: Advanced
66  AP_GROUPINFO("WIND_MAX", 6, AP_AHRS, _wind_max, 0.0f),
67 
68  // NOTE: 7 was BARO_USE
69 
70  // @Param: TRIM_X
71  // @DisplayName: AHRS Trim Roll
72  // @Description: Compensates for the roll angle difference between the control board and the frame. Positive values make the vehicle roll right.
73  // @Units: rad
74  // @Range: -0.1745 +0.1745
75  // @Increment: 0.01
76  // @User: Standard
77 
78  // @Param: TRIM_Y
79  // @DisplayName: AHRS Trim Pitch
80  // @Description: Compensates for the pitch angle difference between the control board and the frame. Positive values make the vehicle pitch up/back.
81  // @Units: rad
82  // @Range: -0.1745 +0.1745
83  // @Increment: 0.01
84  // @User: Standard
85 
86  // @Param: TRIM_Z
87  // @DisplayName: AHRS Trim Yaw
88  // @Description: Not Used
89  // @Units: rad
90  // @Range: -0.1745 +0.1745
91  // @Increment: 0.01
92  // @User: Advanced
93  AP_GROUPINFO("TRIM", 8, AP_AHRS, _trim, 0),
94 
95  // @Param: ORIENTATION
96  // @DisplayName: Board Orientation
97  // @Description: Overall board orientation relative to the standard orientation for the board type. This rotates the IMU and compass readings to allow the board to be oriented in your vehicle at any 90 or 45 degree angle. This option takes affect on next boot. After changing you will need to re-level your vehicle.
98  // @Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw135,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180,39:Pitch315,40:Roll90Pitch315,100:Custom
99  // @User: Advanced
100  AP_GROUPINFO("ORIENTATION", 9, AP_AHRS, _board_orientation, 0),
101 
102  // @Param: COMP_BETA
103  // @DisplayName: AHRS Velocity Complementary Filter Beta Coefficient
104  // @Description: This controls the time constant for the cross-over frequency used to fuse AHRS (airspeed and heading) and GPS data to estimate ground velocity. Time constant is 0.1/beta. A larger time constant will use GPS data less and a small time constant will use air data less.
105  // @Range: 0.001 0.5
106  // @Increment: .01
107  // @User: Advanced
108  AP_GROUPINFO("COMP_BETA", 10, AP_AHRS, beta, 0.1f),
109 
110  // @Param: GPS_MINSATS
111  // @DisplayName: AHRS GPS Minimum satellites
112  // @Description: Minimum number of satellites visible to use GPS for velocity based corrections attitude correction. This defaults to 6, which is about the point at which the velocity numbers from a GPS become too unreliable for accurate correction of the accelerometers.
113  // @Range: 0 10
114  // @Increment: 1
115  // @User: Advanced
116  AP_GROUPINFO("GPS_MINSATS", 11, AP_AHRS, _gps_minsats, 6),
117 
118  // NOTE: index 12 was for GPS_DELAY, but now removed, fixed delay
119  // of 1 was found to be the best choice
120 
121  // 13 was the old EKF_USE
122 
123 #if AP_AHRS_NAVEKF_AVAILABLE
124  // @Param: EKF_TYPE
125  // @DisplayName: Use NavEKF Kalman filter for attitude and position estimation
126  // @Description: This controls which NavEKF Kalman filter version is used for attitude and position estimation
127  // @Values: 0:Disabled,2:Enable EKF2,3:Enable EKF3
128  // @User: Advanced
129  AP_GROUPINFO("EKF_TYPE", 14, AP_AHRS, _ekf_type, 2),
130 #endif
131 
132  // @Param: CUSTOM_ROLL
133  // @DisplayName: Board orientation roll offset
134  // @Description: Autopilot mounting position roll offset. Positive values = roll right, negative values = roll left. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
135  // @Range: -180 180
136  // @Units: deg
137  // @Increment: 1
138  // @User: Advanced
139  AP_GROUPINFO("CUSTOM_ROLL", 15, AP_AHRS, _custom_roll, 0),
140 
141  // @Param: CUSTOM_PIT
142  // @DisplayName: Board orientation pitch offset
143  // @Description: Autopilot mounting position pitch offset. Positive values = pitch up, negative values = pitch down. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
144  // @Range: -180 180
145  // @Units: deg
146  // @Increment: 1
147  // @User: Advanced
148  AP_GROUPINFO("CUSTOM_PIT", 16, AP_AHRS, _custom_pitch, 0),
149 
150  // @Param: CUSTOM_YAW
151  // @DisplayName: Board orientation yaw offset
152  // @Description: Autopilot mounting position yaw offset. Positive values = yaw right, negative values = yaw left. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
153  // @Range: -180 180
154  // @Units: deg
155  // @Increment: 1
156  // @User: Advanced
157  AP_GROUPINFO("CUSTOM_YAW", 17, AP_AHRS, _custom_yaw, 0),
158 
160 };
161 
162 // return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)
164 {
165  const uint8_t primary_gyro = get_primary_gyro_index();
166  return AP::ins().get_gyro(primary_gyro) + get_gyro_drift();
167 }
168 
169 // return airspeed estimate if available
170 bool AP_AHRS::airspeed_estimate(float *airspeed_ret) const
171 {
172  if (airspeed_sensor_enabled()) {
173  *airspeed_ret = _airspeed->get_airspeed();
174  if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
175  // constrain the airspeed by the ground speed
176  // and AHRS_WIND_MAX
177  const float gnd_speed = AP::gps().ground_speed();
178  float true_airspeed = *airspeed_ret * get_EAS2TAS();
179  true_airspeed = constrain_float(true_airspeed,
180  gnd_speed - _wind_max,
181  gnd_speed + _wind_max);
182  *airspeed_ret = true_airspeed / get_EAS2TAS();
183  }
184  return true;
185  }
186  return false;
187 }
188 
189 // set_trim
191 {
192  Vector3f trim;
195  _trim.set_and_save(trim);
196 }
197 
198 // add_trim - adjust the roll and pitch trim up to a total of 10 degrees
199 void AP_AHRS::add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom)
200 {
201  Vector3f trim = _trim.get();
202 
203  // add new trim
204  trim.x = constrain_float(trim.x + roll_in_radians, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT));
205  trim.y = constrain_float(trim.y + pitch_in_radians, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT));
206 
207  // set new trim values
208  _trim.set(trim);
209 
210  // save to eeprom
211  if( save_to_eeprom ) {
212  _trim.save();
213  }
214 }
215 
216 // Set the board mounting orientation, may be called while disarmed
218 {
219  enum Rotation orientation = (enum Rotation)_board_orientation.get();
220  if (orientation != ROTATION_CUSTOM) {
221  AP::ins().set_board_orientation(orientation);
222  if (_compass != nullptr) {
223  _compass->set_board_orientation(orientation);
224  }
225  } else {
228  if (_compass != nullptr) {
230  }
231  }
232 }
233 
234 // return a ground speed estimate in m/s
236 {
237  // Generate estimate of ground speed vector using air data system
238  Vector2f gndVelADS;
239  Vector2f gndVelGPS;
240  float airspeed;
241  const bool gotAirspeed = airspeed_estimate_true(&airspeed);
242  const bool gotGPS = (AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D);
243  if (gotAirspeed) {
244  const Vector3f wind = wind_estimate();
245  const Vector2f wind2d(wind.x, wind.y);
246  const Vector2f airspeed_vector(cosf(yaw) * airspeed, sinf(yaw) * airspeed);
247  gndVelADS = airspeed_vector - wind2d;
248  }
249 
250  // Generate estimate of ground speed vector using GPS
251  if (gotGPS) {
252  const float cog = radians(AP::gps().ground_course_cd()*0.01f);
253  gndVelGPS = Vector2f(cosf(cog), sinf(cog)) * AP::gps().ground_speed();
254  }
255  // If both ADS and GPS data is available, apply a complementary filter
256  if (gotAirspeed && gotGPS) {
257  // The LPF is applied to the GPS and the HPF is applied to the air data estimate
258  // before the two are summed
259  //Define filter coefficients
260  // alpha and beta must sum to one
261  // beta = dt/Tau, where
262  // dt = filter time step (0.1 sec if called by nav loop)
263  // Tau = cross-over time constant (nominal 2 seconds)
264  // More lag on GPS requires Tau to be bigger, less lag allows it to be smaller
265  // To-Do - set Tau as a function of GPS lag.
266  const float alpha = 1.0f - beta;
267  // Run LP filters
268  _lp = gndVelGPS * beta + _lp * alpha;
269  // Run HP filters
270  _hp = (gndVelADS - _lastGndVelADS) + _hp * alpha;
271  // Save the current ADS ground vector for the next time step
272  _lastGndVelADS = gndVelADS;
273  // Sum the HP and LP filter outputs
274  return _hp + _lp;
275  }
276  // Only ADS data is available return ADS estimate
277  if (gotAirspeed && !gotGPS) {
278  return gndVelADS;
279  }
280  // Only GPS data is available so return GPS estimate
281  if (!gotAirspeed && gotGPS) {
282  return gndVelGPS;
283  }
284  return Vector2f(0.0f, 0.0f);
285 }
286 
287 /*
288  calculate sin and cos of roll/pitch/yaw from a body_to_ned rotation matrix
289  */
290 void AP_AHRS::calc_trig(const Matrix3f &rot,
291  float &cr, float &cp, float &cy,
292  float &sr, float &sp, float &sy) const
293 {
294  Vector2f yaw_vector(rot.a.x, rot.b.x);
295 
296  if (fabsf(yaw_vector.x) > 0 ||
297  fabsf(yaw_vector.y) > 0) {
298  yaw_vector.normalize();
299  }
300  sy = constrain_float(yaw_vector.y, -1.0f, 1.0f);
301  cy = constrain_float(yaw_vector.x, -1.0f, 1.0f);
302 
303  // sanity checks
304  if (yaw_vector.is_inf() || yaw_vector.is_nan()) {
305  sy = 0.0f;
306  cy = 1.0f;
307  }
308 
309  const float cx2 = rot.c.x * rot.c.x;
310  if (cx2 >= 1.0f) {
311  cp = 0;
312  cr = 1.0f;
313  } else {
314  cp = safe_sqrt(1 - cx2);
315  cr = rot.c.z / cp;
316  }
317  cp = constrain_float(cp, 0.0f, 1.0f);
318  cr = constrain_float(cr, -1.0f, 1.0f); // this relies on constrain_float() of infinity doing the right thing
319 
320  sp = -rot.c.x;
321 
322  if (!is_zero(cp)) {
323  sr = rot.c.y / cp;
324  }
325 
326  if (is_zero(cp) || isinf(cr) || isnan(cr) || isinf(sr) || isnan(sr)) {
327  float r, p, y;
328  rot.to_euler(&r, &p, &y);
329  cr = cosf(r);
330  sr = sinf(r);
331  }
332 }
333 
334 // update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude
335 // should be called after _dcm_matrix is updated
337 {
338  if (_last_trim != _trim.get()) {
339  _last_trim = _trim.get();
342  }
343 
347 }
348 
349 /*
350  update the centi-degree values
351  */
353 {
354  roll_sensor = degrees(roll) * 100;
355  pitch_sensor = degrees(pitch) * 100;
356  yaw_sensor = degrees(yaw) * 100;
357  if (yaw_sensor < 0)
358  yaw_sensor += 36000;
359 }
360 
361 /*
362  create a rotated view of AP_AHRS
363  */
365 {
366  if (_view != nullptr) {
367  // can only have one
368  return nullptr;
369  }
370  _view = new AP_AHRS_View(*this, rotation);
371  return _view;
372 }
373 
374 /*
375  * Update AOA and SSA estimation based on airspeed, velocity vector and wind vector
376  *
377  * Based on:
378  * "On estimation of wind velocity, angle-of-attack and sideslip angle of small UAVs using standard sensors" by
379  * Tor A. Johansen, Andrea Cristofaro, Kim Sorensen, Jakob M. Hansen, Thor I. Fossen
380  *
381  * "Multi-Stage Fusion Algorithm for Estimation of Aerodynamic Angles in Mini Aerial Vehicle" by
382  * C.Ramprasadh and Hemendra Arya
383  *
384  * "ANGLE OF ATTACK AND SIDESLIP ESTIMATION USING AN INERTIAL REFERENCE PLATFORM" by
385  * JOSEPH E. ZEIS, JR., CAPTAIN, USAF
386  */
388 {
389 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
390  const uint32_t now = AP_HAL::millis();
391  if (now - _last_AOA_update_ms < 50) {
392  // don't update at more than 20Hz
393  return;
394  }
395  _last_AOA_update_ms = now;
396 
397  Vector3f aoa_velocity, aoa_wind;
398 
399  // get velocity and wind
400  if (get_velocity_NED(aoa_velocity) == false) {
401  return;
402  }
403 
404  aoa_wind = wind_estimate();
405 
406  // Rotate vectors to the body frame and calculate velocity and wind
407  const Matrix3f &rot = get_rotation_body_to_ned();
408  aoa_velocity = rot.mul_transpose(aoa_velocity);
409  aoa_wind = rot.mul_transpose(aoa_wind);
410 
411  // calculate relative velocity in body coordinates
412  aoa_velocity = aoa_velocity - aoa_wind;
413  const float vel_len = aoa_velocity.length();
414 
415  // do not calculate if speed is too low
416  if (vel_len < 2.0) {
417  _AOA = 0;
418  _SSA = 0;
419  return;
420  }
421 
422  // Calculate AOA and SSA
423  if (aoa_velocity.x > 0) {
424  _AOA = degrees(atanf(aoa_velocity.z / aoa_velocity.x));
425  } else {
426  _AOA = 0;
427  }
428 
429  _SSA = degrees(safe_asin(aoa_velocity.y / vel_len));
430 #endif
431 }
432 
433 // return current AOA
434 float AP_AHRS::getAOA(void)
435 {
436  update_AOA_SSA();
437  return _AOA;
438 }
439 
440 // return calculated SSA
441 float AP_AHRS::getSSA(void)
442 {
443  update_AOA_SSA();
444  return _SSA;
445 }
446 
447 // rotate a 2D vector from earth frame to body frame
449 {
450  return Vector2f(ef.x * _cos_yaw + ef.y * _sin_yaw,
451  -ef.x * _sin_yaw + ef.y * _cos_yaw);
452 }
453 
454 // rotate a 2D vector from earth frame to body frame
456 {
457  return Vector2f(bf.x * _cos_yaw - bf.y * _sin_yaw,
458  bf.x * _sin_yaw + bf.y * _cos_yaw);
459 }
460 
461 // log ahrs home and EKF origin to dataflash
463 {
465  if (df == nullptr) {
466  return;
467  }
468 #if AP_AHRS_NAVEKF_AVAILABLE
469  // log ekf origin if set
470  Location ekf_orig;
471  if (get_origin(ekf_orig)) {
473  }
474 #endif
475 
476  // log ahrs home if set
477  if (home_is_set()) {
479  }
480 }
481 
482 
483 // singleton instance
485 
486 namespace AP {
487 
489 {
490  return *AP_AHRS::get_singleton();
491 }
492 
493 }
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_AHRS.h:416
bool is_nan(void) const
Definition: vector2.cpp:66
void to_euler(float *roll, float *pitch, float *yaw) const
Definition: matrix3.cpp:49
virtual bool get_velocity_NED(Vector3f &vec) const
Definition: AP_AHRS.h:309
Vector2< float > Vector2f
Definition: vector2.h:239
float roll
Definition: AP_AHRS.h:224
AP_Int8 _wind_max
Definition: AP_AHRS.h:582
bool airspeed_estimate_true(float *airspeed_ret) const
Definition: AP_AHRS.h:281
void set_board_orientation(enum Rotation orientation, Matrix3f *custom_rotation=nullptr)
Definition: AP_Compass.h:213
float getAOA(void)
Definition: AP_AHRS.cpp:434
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
float _sin_roll
Definition: AP_AHRS.h:661
AP_Airspeed * _airspeed
Definition: AP_AHRS.h:624
float _AOA
Definition: AP_AHRS.h:670
const Vector3f & get_gyro(uint8_t i) const
#define ToRad(x)
Definition: AP_Common.h:53
virtual Vector3f wind_estimate(void) const =0
AP_Int8 _board_orientation
Definition: AP_AHRS.h:583
bool is_inf(void) const
Definition: vector2.cpp:72
float get_airspeed(uint8_t i) const
Definition: AP_Airspeed.h:53
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float pitch
Definition: AP_AHRS.h:225
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
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
void Log_Write_Home_And_Origin()
Definition: AP_AHRS.cpp:462
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
Rotation
Definition: rotations.h:27
static AP_AHRS * get_singleton()
Definition: AP_AHRS.h:83
AP_AHRS_View * create_view(enum Rotation rotation)
Definition: AP_AHRS.cpp:364
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
int32_t roll_sensor
Definition: AP_AHRS.h:229
Matrix3f _rotation_vehicle_body_to_autopilot_body
Definition: AP_AHRS.h:638
Vector2f _lp
Definition: AP_AHRS.h:650
Matrix3< T > transposed(void) const
Definition: matrix3.cpp:189
T y
Definition: vector2.h:37
Vector3f _last_trim
Definition: AP_AHRS.h:636
Matrix3f _custom_rotation
Definition: AP_AHRS.h:591
Vector2f _hp
Definition: AP_AHRS.h:651
virtual void set_trim(Vector3f new_trim)
Definition: AP_AHRS.cpp:190
Definition: AP_AHRS.cpp:486
float _sin_pitch
Definition: AP_AHRS.h:661
float ground_speed(uint8_t instance) const
Definition: AP_GPS.h:232
float _sin_yaw
Definition: AP_AHRS.h:661
int32_t pitch_sensor
Definition: AP_AHRS.h:230
void update_cd_values(void)
Definition: AP_AHRS.cpp:352
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
float getSSA(void)
Definition: AP_AHRS.cpp:441
T y
Definition: vector3.h:67
friend class AP_AHRS_View
Definition: AP_AHRS.h:53
Vector3< T > c
Definition: matrix3.h:48
uint32_t millis()
Definition: system.cpp:157
void set_board_orientation(enum Rotation orientation, Matrix3f *custom_rotation=nullptr)
Matrix3f _rotation_autopilot_body_to_vehicle_body
Definition: AP_AHRS.h:637
Vector2f rotate_body_to_earth2D(const Vector2f &bf) const
Definition: AP_AHRS.cpp:455
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
Vector3f get_gyro_latest(void) const
Definition: AP_AHRS.cpp:163
AP_Float _custom_roll
Definition: AP_AHRS.h:587
T z
Definition: vector3.h:67
virtual const Vector3f & get_gyro_drift(void) const =0
AP_Float _custom_yaw
Definition: AP_AHRS.h:589
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
Receiving valid messages and 2D lock.
Definition: AP_GPS.h:99
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
AP_Float beta
Definition: AP_AHRS.h:580
float safe_asin(const T v)
Definition: AP_Math.cpp:43
struct Location _home
Definition: AP_AHRS.h:655
float length(void) const
Definition: vector3.cpp:288
Vector3< T > mul_transpose(const Vector3< T > &v) const
Definition: matrix3.cpp:165
AP_Float _custom_pitch
Definition: AP_AHRS.h:588
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
float _cos_roll
Definition: AP_AHRS.h:660
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
AP_AHRS & ahrs()
Definition: AP_AHRS.cpp:488
#define AP_AHRS_TRIM_LIMIT
Definition: AP_AHRS.h:34
AP_AHRS_View * _view
Definition: AP_AHRS.h:667
void Log_Write_Origin(uint8_t origin_type, const Location &loc)
Definition: LogFile.cpp:1594
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void normalize()
Definition: vector2.h:140
virtual bool get_origin(Location &ret) const
Definition: AP_AHRS.h:464
Compass * _compass
Definition: AP_AHRS.h:618
virtual uint8_t get_primary_gyro_index(void) const
Definition: AP_AHRS.h:188
AP_InertialSensor & ins()
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
float _SSA
Definition: AP_AHRS.h:670
Vector3< T > b
Definition: matrix3.h:48
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
void update_trig(void)
Definition: AP_AHRS.cpp:336
#define degrees(x)
Definition: moduletest.c:23
AP_Vector3f _trim
Definition: AP_AHRS.h:633
bool home_is_set(void) const
Definition: AP_AHRS.h:449
int32_t yaw_sensor
Definition: AP_AHRS.h:231
float _cos_yaw
Definition: AP_AHRS.h:660
Vector3< T > a
Definition: matrix3.h:48
float _cos_pitch
Definition: AP_AHRS.h:660
static AP_AHRS * _singleton
Definition: AP_AHRS.h:674
#define AP_GROUPEND
Definition: AP_Param.h:121
T x
Definition: vector3.h:67
uint32_t _last_AOA_update_ms
Definition: AP_AHRS.h:671