APM:Libraries
AP_AHRS_DCM.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  * DCM based AHRS (Attitude Heading Reference System) interface for
20  * ArduPilot
21  *
22  */
23 
24 class AP_AHRS_DCM : public AP_AHRS {
25 public:
27  : AP_AHRS()
28  , _error_rp(1.0f)
29  , _error_yaw(1.0f)
30  , _mag_earth(1, 0)
31  , _imu1_weight(0.5f)
32  {
34 
35  // these are experimentally derived from the simulator
36  // with large drift levels
37  _ki = 0.0087f;
38  _ki_yaw = 0.01f;
39  }
40 
41  /* Do not allow copies */
42  AP_AHRS_DCM(const AP_AHRS_DCM &other) = delete;
43  AP_AHRS_DCM &operator=(const AP_AHRS_DCM&) = delete;
44 
45 
46  // return the smoothed gyro vector corrected for drift
47  const Vector3f &get_gyro() const override {
48  return _omega;
49  }
50 
51  // return rotation matrix representing rotaton from body to earth axes
52  const Matrix3f &get_rotation_body_to_ned() const override {
53  return _body_dcm_matrix;
54  }
55 
56  // return the current drift correction integrator value
57  const Vector3f &get_gyro_drift() const override {
58  return _omega_I;
59  }
60 
61  // reset the current gyro drift estimate
62  // should be called if gyro offsets are recalculated
63  void reset_gyro_drift() override;
64 
65  // Methods
66  void update(bool skip_ins_update=false) override;
67  void reset(bool recover_eulers = false) override;
68 
69  // reset the current attitude, used on new IMU calibration
70  void reset_attitude(const float &roll, const float &pitch, const float &yaw) override;
71 
72  // dead-reckoning support
73  virtual bool get_position(struct Location &loc) const override;
74 
75  // status reporting
76  float get_error_rp() const override {
77  return _error_rp;
78  }
79  float get_error_yaw() const override {
80  return _error_yaw;
81  }
82 
83  // return a wind estimation vector, in m/s
84  Vector3f wind_estimate() const override {
85  return _wind;
86  }
87 
88  void get_relative_position_D_home(float &posD) const override;
89 
90  // return an airspeed estimate if available. return true
91  // if we have an estimate
92  bool airspeed_estimate(float *airspeed_ret) const override;
93 
94  bool use_compass() override;
95 
96  void set_home(const Location &loc) override;
97  void estimate_wind(void);
98 
99  // is the AHRS subsystem healthy?
100  bool healthy() const override;
101 
102  // time that the AHRS has been up
103  uint32_t uptime_ms() const override;
104 
105 private:
106  float _ki;
107  float _ki_yaw;
108 
109  // Methods
110  void matrix_update(float _G_Dt);
111  void normalize(void);
112  void check_matrix(void);
113  bool renorm(Vector3f const &a, Vector3f &result);
114  void drift_correction(float deltat);
115  void drift_correction_yaw(void);
116  float yaw_error_compass();
117  void euler_angles(void);
118  bool have_gps(void) const;
119  bool use_fast_gains(void) const;
120 
121  // primary representation of attitude of board used for all inertial calculations
123 
124  // primary representation of attitude of flight vehicle body
126 
127  Vector3f _omega_P; // accel Omega proportional correction
128  Vector3f _omega_yaw_P; // proportional yaw correction
129  Vector3f _omega_I; // Omega Integrator correction
132  Vector3f _omega; // Corrected Gyro_Vector data
133 
134  // variables to cope with delaying the GA sum to match GPS lag
135  Vector3f ra_delayed(uint8_t instance, const Vector3f &ra);
137 
138  // P term gain based on spin rate
139  float _P_gain(float spin_rate);
140 
141  // P term yaw gain based on rate of change of horiz velocity
142  float _yaw_gain(void) const;
143 
144  // state to support status reporting
147  float _error_rp;
148  float _error_yaw;
149 
150  // time in millis when we last got a GPS heading
152 
153  // state of accel drift correction
156  float _ra_deltat;
157  uint32_t _ra_sum_start;
158 
159  // the earths magnetic field
162 
163  // whether we have GPS lock
165 
166  // the lat/lng where we last had GPS lock
167  int32_t _last_lat;
168  int32_t _last_lng;
169 
170  // position offset from last GPS lock
173 
174  // whether we have a position estimate
176 
177  // support for wind estimation
180  uint32_t _last_wind_time;
183 
184  // estimated wind in m/s
186 
188 
189  // last time AHRS failed in milliseconds
191 
192  // time when DCM was last reset
194 };
void estimate_wind(void)
float _ki_yaw
Definition: AP_AHRS_DCM.h:107
float roll
Definition: AP_AHRS.h:224
bool use_fast_gains(void) const
float _P_gain(float spin_rate)
void set_home(const Location &loc) override
float get_error_rp() const override
Definition: AP_AHRS_DCM.h:76
Vector3f _omega
Definition: AP_AHRS_DCM.h:132
Vector3f _omega_yaw_P
Definition: AP_AHRS_DCM.h:128
bool use_compass() override
Matrix3f _dcm_matrix
Definition: AP_AHRS_DCM.h:122
void get_relative_position_D_home(float &posD) const override
Vector3f _last_vel
Definition: AP_AHRS_DCM.h:179
float _position_offset_east
Definition: AP_AHRS_DCM.h:172
Vector2f _mag_earth
Definition: AP_AHRS_DCM.h:161
Vector3f _last_fuse
Definition: AP_AHRS_DCM.h:178
int32_t _last_lng
Definition: AP_AHRS_DCM.h:168
Vector3f _last_velocity
Definition: AP_AHRS_DCM.h:155
float pitch
Definition: AP_AHRS.h:225
float _last_declination
Definition: AP_AHRS_DCM.h:160
Matrix3f _body_dcm_matrix
Definition: AP_AHRS_DCM.h:125
float yaw
Definition: AP_AHRS.h:226
void update(bool skip_ins_update=false) override
Definition: AP_AHRS_DCM.cpp:50
Vector3f _ra_sum[INS_MAX_INSTANCES]
Definition: AP_AHRS_DCM.h:154
const Vector3f & get_gyro() const override
Definition: AP_AHRS_DCM.h:47
void euler_angles(void)
bool have_gps(void) const
const char * result
Definition: Printf.cpp:16
void reset_attitude(const float &roll, const float &pitch, const float &yaw) override
void reset_gyro_drift() override
Definition: AP_AHRS_DCM.cpp:41
uint32_t _last_consistent_heading
Definition: AP_AHRS_DCM.h:182
bool renorm(Vector3f const &a, Vector3f &result)
const Vector3f & get_gyro_drift() const override
Definition: AP_AHRS_DCM.h:57
bool healthy() const override
bool airspeed_estimate(float *airspeed_ret) const override
uint32_t _last_wind_time
Definition: AP_AHRS_DCM.h:180
uint32_t _ra_sum_start
Definition: AP_AHRS_DCM.h:157
uint32_t _last_failure_ms
Definition: AP_AHRS_DCM.h:190
virtual bool get_position(struct Location &loc) const override
float yaw_error_compass()
#define f(i)
void drift_correction(float deltat)
void matrix_update(float _G_Dt)
Vector3f _omega_P
Definition: AP_AHRS_DCM.h:127
const Matrix3f & get_rotation_body_to_ned() const override
Definition: AP_AHRS_DCM.h:52
float get_error_yaw() const override
Definition: AP_AHRS_DCM.h:79
float _yaw_gain(void) const
float _imu1_weight
Definition: AP_AHRS_DCM.h:187
float _error_rp
Definition: AP_AHRS_DCM.h:147
Vector3f _omega_I
Definition: AP_AHRS_DCM.h:129
Vector3f _wind
Definition: AP_AHRS_DCM.h:185
void check_matrix(void)
Vector3f wind_estimate() const override
Definition: AP_AHRS_DCM.h:84
Vector3f ra_delayed(uint8_t instance, const Vector3f &ra)
bool _have_gps_lock
Definition: AP_AHRS_DCM.h:164
float _position_offset_north
Definition: AP_AHRS_DCM.h:171
uint16_t _renorm_val_count
Definition: AP_AHRS_DCM.h:146
void normalize(void)
void drift_correction_yaw(void)
uint32_t uptime_ms() const override
float _last_airspeed
Definition: AP_AHRS_DCM.h:181
float _ra_deltat
Definition: AP_AHRS_DCM.h:156
void reset(bool recover_eulers=false) override
float _error_yaw
Definition: AP_AHRS_DCM.h:148
AP_AHRS_DCM & operator=(const AP_AHRS_DCM &)=delete
bool _have_position
Definition: AP_AHRS_DCM.h:175
float _omega_I_sum_time
Definition: AP_AHRS_DCM.h:131
float _renorm_val_sum
Definition: AP_AHRS_DCM.h:145
Vector3f _ra_delay_buffer[INS_MAX_INSTANCES]
Definition: AP_AHRS_DCM.h:136
#define INS_MAX_INSTANCES
int32_t _last_lat
Definition: AP_AHRS_DCM.h:167
Vector3f _omega_I_sum
Definition: AP_AHRS_DCM.h:130
void identity(void)
Definition: matrix3.h:219
uint32_t _last_startup_ms
Definition: AP_AHRS_DCM.h:193
uint32_t _gps_last_update
Definition: AP_AHRS_DCM.h:151