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_View.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 View class - for creating a 2nd view of the vehicle attitude
20
*
21
*/
22
23
#include "AP_AHRS.h"
24
25
// fwd declarations to avoid include errors
26
class AC_AttitudeControl;
27
class AC_PosControl;
28
29
class AP_AHRS_View
30
{
31
public:
32
// Constructor
33
AP_AHRS_View(AP_AHRS &ahrs, enum Rotation rotation, float pitch_trim_deg=0);
34
35
// update state
36
void update();
37
38
// empty virtual destructor
39
virtual ~AP_AHRS_View() {}
40
41
// return a smoothed and corrected gyro vector
42
const Vector3f &get_gyro(void) const {
43
return gyro;
44
}
45
46
// return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)
47
Vector3f get_gyro_latest(void) const;
48
49
// return a DCM rotation matrix representing our current attitude in this view
50
const Matrix3f &get_rotation_body_to_ned(void) const {
51
return rot_body_to_ned;
52
}
53
54
// return a Quaternion representing our current attitude in this view
55
void get_quat_body_to_ned(Quaternion &quat) const {
56
quat.from_rotation_matrix(rot_body_to_ned);
57
}
58
59
// apply pitch trim
60
void set_pitch_trim(float trim_deg);
61
62
// helper trig value accessors
63
float cos_roll() const {
64
return trig.cos_roll;
65
}
66
float cos_pitch() const {
67
return trig.cos_pitch;
68
}
69
float cos_yaw() const {
70
return trig.cos_yaw;
71
}
72
float sin_roll() const {
73
return trig.sin_roll;
74
}
75
float sin_pitch() const {
76
return trig.sin_pitch;
77
}
78
float sin_yaw() const {
79
return trig.sin_yaw;
80
}
81
82
83
/*
84
wrappers around ahrs functions which pass-thru directly. See
85
AP_AHRS.h for description of each function
86
*/
87
bool get_location(Location &loc) const WARN_IF_UNUSED {
88
return ahrs.get_location(loc);
89
}
90
91
bool wind_estimate(Vector3f &wind) {
92
return ahrs.wind_estimate(wind);
93
}
94
95
bool airspeed_estimate(float &airspeed_ret) const WARN_IF_UNUSED {
96
return ahrs.airspeed_estimate(airspeed_ret);
97
}
98
99
bool airspeed_estimate_true(float &airspeed_ret) const WARN_IF_UNUSED {
100
return ahrs.airspeed_estimate_true(airspeed_ret);
101
}
102
103
float get_EAS2TAS(void) const {
104
return ahrs.get_EAS2TAS();
105
}
106
107
Vector2f groundspeed_vector(void) {
108
return ahrs.groundspeed_vector();
109
}
110
111
bool get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED {
112
return ahrs.get_velocity_NED(vec);
113
}
114
115
bool get_relative_position_NED_home(Vector3f &vec) const WARN_IF_UNUSED {
116
return ahrs.get_relative_position_NED_home(vec);
117
}
118
119
bool get_relative_position_NED_origin(Vector3f &vec) const WARN_IF_UNUSED {
120
return ahrs.get_relative_position_NED_origin(vec);
121
}
122
123
bool get_relative_position_NE_home(Vector2f &vecNE) const WARN_IF_UNUSED {
124
return ahrs.get_relative_position_NE_home(vecNE);
125
}
126
127
bool get_relative_position_NE_origin(Vector2f &vecNE) const WARN_IF_UNUSED {
128
return ahrs.get_relative_position_NE_origin(vecNE);
129
}
130
131
void get_relative_position_D_home(float &posD) const {
132
ahrs.get_relative_position_D_home(posD);
133
}
134
135
bool get_relative_position_D_origin(float &posD) const WARN_IF_UNUSED {
136
return ahrs.get_relative_position_D_origin(posD);
137
}
138
139
float groundspeed(void) {
140
return ahrs.groundspeed();
141
}
142
143
const Vector3f &get_accel_ef(void) const {
144
return ahrs.get_accel_ef();
145
}
146
147
uint32_t getLastPosNorthEastReset(Vector2f &pos) WARN_IF_UNUSED {
148
return ahrs.getLastPosNorthEastReset(pos);
149
}
150
151
uint32_t getLastPosDownReset(float &posDelta) WARN_IF_UNUSED {
152
return ahrs.getLastPosDownReset(posDelta);
153
}
154
155
// rotate a 2D vector from earth frame to body frame
156
// in result, x is forward, y is right
157
Vector2f earth_to_body2D(const Vector2f &ef_vector) const;
158
159
// rotate a 2D vector from earth frame to body frame
160
// in input, x is forward, y is right
161
Vector2f body_to_earth2D(const Vector2f &bf) const;
162
163
// return the average size of the roll/pitch error estimate
164
// since last call
165
float get_error_rp(void) const {
166
return ahrs.get_error_rp();
167
}
168
169
// return the average size of the yaw error estimate
170
// since last call
171
float get_error_yaw(void) const {
172
return ahrs.get_error_yaw();
173
}
174
175
// Logging Functions
176
void Write_AttitudeView(const Vector3f &targets) const;
177
178
float roll;
179
float pitch;
180
float yaw;
181
int32_t roll_sensor;
182
int32_t pitch_sensor;
183
int32_t yaw_sensor;
184
185
186
// get current rotation
187
// note that this may not be the rotation were actually using, see _pitch_trim_deg
188
enum Rotation get_rotation(void) const {
189
return rotation;
190
}
191
192
// get pitch trim (deg)
193
float get_pitch_trim() const { return _pitch_trim_deg; }
194
195
// Rotate vector from AHRS reference frame to AHRS view refences frame
196
void rotate(Vector3f &vec) const;
197
198
private:
199
const enum Rotation rotation;
200
AP_AHRS &ahrs;
201
202
// body frame rotation for this View
203
Matrix3f rot_view;
204
// transpose of rot_view
205
Matrix3f rot_view_T;
206
Matrix3f rot_body_to_ned;
207
Vector3f gyro;
208
209
struct {
210
float cos_roll;
211
float cos_pitch;
212
float cos_yaw;
213
float sin_roll;
214
float sin_pitch;
215
float sin_yaw;
216
} trig;
217
218
float y_angle;
219
float _pitch_trim_deg;
220
};
221
222