APM:Libraries
AP_AHRS_View.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 View class - for creating a 2nd view of the vehicle attitude
20  *
21  */
22 
23 #include "AP_AHRS.h"
24 
26 {
27 public:
28  // Constructor
30 
31  // update state
32  void update(bool skip_ins_update=false);
33 
34  // empty virtual destructor
35  virtual ~AP_AHRS_View() {}
36 
37  // return a smoothed and corrected gyro vector
38  const Vector3f &get_gyro(void) const {
39  return gyro;
40  }
41 
42  // return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)
43  Vector3f get_gyro_latest(void) const;
44 
45  // return a DCM rotation matrix representing our current
46  // attitude in this view
47  const Matrix3f &get_rotation_body_to_ned(void) const {
48  return rot_body_to_ned;
49  }
50 
51  // helper trig value accessors
52  float cos_roll() const {
53  return trig.cos_roll;
54  }
55  float cos_pitch() const {
56  return trig.cos_pitch;
57  }
58  float cos_yaw() const {
59  return trig.cos_yaw;
60  }
61  float sin_roll() const {
62  return trig.sin_roll;
63  }
64  float sin_pitch() const {
65  return trig.sin_pitch;
66  }
67  float sin_yaw() const {
68  return trig.sin_yaw;
69  }
70 
71 
72  /*
73  wrappers around ahrs functions which pass-thru directly. See
74  AP_AHRS.h for description of each function
75  */
76  bool get_position(struct Location &loc) const {
77  return ahrs.get_position(loc);
78  }
79 
81  return ahrs.wind_estimate();
82  }
83 
84  bool airspeed_estimate(float *airspeed_ret) const {
85  return ahrs.airspeed_estimate(airspeed_ret);
86  }
87 
88  bool airspeed_estimate_true(float *airspeed_ret) const {
89  return ahrs.airspeed_estimate_true(airspeed_ret);
90  }
91 
92  float get_EAS2TAS(void) const {
93  return ahrs.get_EAS2TAS();
94  }
95 
97  return ahrs.groundspeed_vector();
98  }
99 
100  bool get_velocity_NED(Vector3f &vec) const {
101  return ahrs.get_velocity_NED(vec);
102  }
103 
105  return ahrs.get_expected_mag_field_NED(ret);
106  }
107 
109  return ahrs.get_relative_position_NED_home(vec);
110  }
111 
113  return ahrs.get_relative_position_NED_origin(vec);
114  }
115 
117  return ahrs.get_relative_position_NE_home(vecNE);
118  }
119 
121  return ahrs.get_relative_position_NE_origin(vecNE);
122  }
123 
124  void get_relative_position_D_home(float &posD) const {
125  ahrs.get_relative_position_D_home(posD);
126  }
127 
128  bool get_relative_position_D_origin(float &posD) const {
129  return ahrs.get_relative_position_D_origin(posD);
130  }
131 
132  float groundspeed(void) {
133  return ahrs.groundspeed();
134  }
135 
136  const Vector3f &get_accel_ef_blended(void) const {
137  return ahrs.get_accel_ef_blended();
138  }
139 
140  uint32_t getLastPosNorthEastReset(Vector2f &pos) const {
141  return ahrs.getLastPosNorthEastReset(pos);
142  }
143 
144  uint32_t getLastPosDownReset(float &posDelta) const {
145  return ahrs.getLastPosDownReset(posDelta);
146  }
147 
148  // rotate a 2D vector from earth frame to body frame
149  // in result, x is forward, y is right
150  Vector2f rotate_earth_to_body2D(const Vector2f &ef_vector) const;
151 
152  // rotate a 2D vector from earth frame to body frame
153  // in input, x is forward, y is right
154  Vector2f rotate_body_to_earth2D(const Vector2f &bf) const;
155 
156  // return the average size of the roll/pitch error estimate
157  // since last call
158  float get_error_rp(void) const {
159  return ahrs.get_error_rp();
160  }
161 
162  // return the average size of the yaw error estimate
163  // since last call
164  float get_error_yaw(void) const {
165  return ahrs.get_error_yaw();
166  }
167 
168  float roll;
169  float pitch;
170  float yaw;
171  int32_t roll_sensor;
172  int32_t pitch_sensor;
173  int32_t yaw_sensor;
174 
175 private:
176  const enum Rotation rotation;
178 
182 
183  struct {
184  float cos_roll;
185  float cos_pitch;
186  float cos_yaw;
187  float sin_roll;
188  float sin_pitch;
189  float sin_yaw;
190  } trig;
191 };
Vector2f rotate_earth_to_body2D(const Vector2f &ef_vector) const
virtual uint32_t getLastPosNorthEastReset(Vector2f &pos) const
Definition: AP_AHRS.h:495
virtual bool get_velocity_NED(Vector3f &vec) const
Definition: AP_AHRS.h:309
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
int32_t pitch_sensor
Definition: AP_AHRS_View.h:172
Vector3f gyro
Definition: AP_AHRS_View.h:181
AP_AHRS_View(AP_AHRS &ahrs, enum Rotation rotation)
virtual const Vector3f & get_accel_ef_blended(void) const
Definition: AP_AHRS.h:201
struct AP_AHRS_View::@4 trig
bool get_position(struct Location &loc) const
Definition: AP_AHRS_View.h:76
Matrix3f rot_body_to_ned
Definition: AP_AHRS_View.h:180
int32_t yaw_sensor
Definition: AP_AHRS_View.h:173
virtual bool get_position(struct Location &loc) const =0
virtual ~AP_AHRS_View()
Definition: AP_AHRS_View.h:35
virtual bool get_relative_position_NED_home(Vector3f &vec) const
Definition: AP_AHRS.h:326
virtual Vector3f wind_estimate(void) const =0
virtual bool get_relative_position_NED_origin(Vector3f &vec) const
Definition: AP_AHRS.h:333
const Matrix3f & get_rotation_body_to_ned(void) const
Definition: AP_AHRS_View.h:47
virtual float get_error_yaw(void) const =0
virtual bool get_relative_position_NE_origin(Vector2f &vecNE) const
Definition: AP_AHRS.h:344
float sin_pitch() const
Definition: AP_AHRS_View.h:64
Vector3f get_gyro_latest(void) const
enum Rotation rotation
Definition: AP_AHRS_View.h:176
virtual bool airspeed_estimate(float *airspeed_ret) const
Definition: AP_AHRS.cpp:170
bool get_expected_mag_field_NED(Vector3f &ret) const
Definition: AP_AHRS_View.h:104
bool airspeed_estimate_true(float *airspeed_ret) const
Definition: AP_AHRS_View.h:88
const Vector3f & get_accel_ef_blended(void) const
Definition: AP_AHRS_View.h:136
float cos_roll() const
Definition: AP_AHRS_View.h:52
Vector2f rotate_body_to_earth2D(const Vector2f &bf) const
virtual Vector2f groundspeed_vector(void)
Definition: AP_AHRS.cpp:235
Rotation
Definition: rotations.h:27
AP_AHRS & ahrs
Definition: AP_AHRS_View.h:177
float get_error_rp(void) const
Definition: AP_AHRS_View.h:158
bool get_velocity_NED(Vector3f &vec) const
Definition: AP_AHRS_View.h:100
const Vector3f & get_gyro(void) const
Definition: AP_AHRS_View.h:38
float get_EAS2TAS(void) const
Definition: AP_AHRS_View.h:92
uint32_t getLastPosDownReset(float &posDelta) const
Definition: AP_AHRS_View.h:144
void update(bool skip_ins_update=false)
bool get_relative_position_NE_home(Vector2f &vecNE) const
Definition: AP_AHRS_View.h:116
virtual bool get_relative_position_NE_home(Vector2f &vecNE) const
Definition: AP_AHRS.h:338
Vector2f groundspeed_vector(void)
Definition: AP_AHRS_View.h:96
virtual float get_error_rp(void) const =0
float sin_yaw() const
Definition: AP_AHRS_View.h:67
bool get_relative_position_NED_origin(Vector3f &vec) const
Definition: AP_AHRS_View.h:112
Matrix3f rot_view
Definition: AP_AHRS_View.h:179
uint32_t getLastPosNorthEastReset(Vector2f &pos) const
Definition: AP_AHRS_View.h:140
float groundspeed(void)
Definition: AP_AHRS_View.h:132
bool get_relative_position_D_origin(float &posD) const
Definition: AP_AHRS_View.h:128
bool get_relative_position_NED_home(Vector3f &vec) const
Definition: AP_AHRS_View.h:108
float sin_roll() const
Definition: AP_AHRS_View.h:61
bool get_relative_position_NE_origin(Vector2f &vecNE) const
Definition: AP_AHRS_View.h:120
float groundspeed(void)
Definition: AP_AHRS.h:359
virtual bool get_expected_mag_field_NED(Vector3f &ret) const
Definition: AP_AHRS.h:314
float get_EAS2TAS(void) const
Definition: AP_AHRS.h:290
Vector3f wind_estimate(void)
Definition: AP_AHRS_View.h:80
float get_error_yaw(void) const
Definition: AP_AHRS_View.h:164
int32_t roll_sensor
Definition: AP_AHRS_View.h:171
float cos_pitch() const
Definition: AP_AHRS_View.h:55
float cos_yaw() const
Definition: AP_AHRS_View.h:58
void get_relative_position_D_home(float &posD) const
Definition: AP_AHRS_View.h:124
virtual void get_relative_position_D_home(float &posD) const =0
virtual bool get_relative_position_D_origin(float &posD) const
Definition: AP_AHRS.h:354
bool airspeed_estimate(float *airspeed_ret) const
Definition: AP_AHRS_View.h:84