Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_AHRS/AP_AHRS_Backend.cpp
9492 views
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
20
#include <AP_Common/Location.h>
21
#include <AP_HAL/AP_HAL.h>
22
#include <AP_Logger/AP_Logger.h>
23
#include <AP_GPS/AP_GPS.h>
24
#include <AP_Baro/AP_Baro.h>
25
#include <AP_Compass/AP_Compass.h>
26
#include <AP_Vehicle/AP_Vehicle_Type.h>
27
28
extern const AP_HAL::HAL& hal;
29
30
void AP_AHRS_Backend::init()
31
{
32
}
33
34
// return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)
35
Vector3f AP_AHRS::get_gyro_latest(void) const
36
{
37
const uint8_t primary_gyro = get_primary_gyro_index();
38
return AP::ins().get_gyro(primary_gyro) + get_gyro_drift();
39
}
40
41
// set_trim
42
void AP_AHRS::set_trim(const Vector3f &new_trim)
43
{
44
const Vector3f trim {
45
constrain_float(new_trim.x, radians(-AP_AHRS_TRIM_LIMIT), radians(AP_AHRS_TRIM_LIMIT)),
46
constrain_float(new_trim.y, radians(-AP_AHRS_TRIM_LIMIT), radians(AP_AHRS_TRIM_LIMIT)),
47
constrain_float(new_trim.z, radians(-AP_AHRS_TRIM_LIMIT), radians(AP_AHRS_TRIM_LIMIT))
48
};
49
_trim.set_and_save(trim);
50
}
51
52
// add_trim - adjust the roll and pitch trim up to a total of 10 degrees
53
void AP_AHRS::add_trim(float roll_in_radians, float pitch_in_radians, bool save_to_eeprom)
54
{
55
Vector3f trim = _trim.get();
56
57
// add new trim
58
trim.x = constrain_float(trim.x + roll_in_radians, radians(-AP_AHRS_TRIM_LIMIT), radians(AP_AHRS_TRIM_LIMIT));
59
trim.y = constrain_float(trim.y + pitch_in_radians, radians(-AP_AHRS_TRIM_LIMIT), radians(AP_AHRS_TRIM_LIMIT));
60
61
// set new trim values
62
_trim.set(trim);
63
64
// save to eeprom
65
if( save_to_eeprom ) {
66
_trim.save();
67
}
68
}
69
70
// Set the board mounting orientation from AHRS_ORIENTATION parameter
71
void AP_AHRS::update_orientation()
72
{
73
const uint32_t now_ms = AP_HAL::millis();
74
if (last_orientation_update_ms != 0 &&
75
now_ms - last_orientation_update_ms < 1000) {
76
// only update once/second
77
return;
78
}
79
80
// never update while armed - unless we've never updated
81
// (e.g. mid-air reboot or ARMING_REQUIRED=NO on Plane):
82
if (hal.util->get_soft_armed() && last_orientation_update_ms != 0) {
83
return;
84
}
85
86
last_orientation_update_ms = now_ms;
87
88
const enum Rotation orientation = (enum Rotation)_board_orientation.get();
89
90
AP::ins().set_board_orientation(orientation);
91
AP::compass().set_board_orientation(orientation);
92
}
93
94
/*
95
calculate sin and cos of roll/pitch/yaw from a body_to_ned rotation matrix
96
*/
97
void AP_AHRS::calc_trig(const Matrix3f &rot,
98
float &cr, float &cp, float &cy,
99
float &sr, float &sp, float &sy) const
100
{
101
Vector2f yaw_vector(rot.a.x, rot.b.x);
102
103
if (fabsf(yaw_vector.x) > 0 ||
104
fabsf(yaw_vector.y) > 0) {
105
yaw_vector.normalize();
106
}
107
sy = constrain_float(yaw_vector.y, -1.0f, 1.0f);
108
cy = constrain_float(yaw_vector.x, -1.0f, 1.0f);
109
110
// sanity checks
111
if (yaw_vector.is_inf() || yaw_vector.is_nan()) {
112
sy = 0.0f;
113
cy = 1.0f;
114
}
115
116
const float cx2 = rot.c.x * rot.c.x;
117
if (cx2 >= 1.0f) {
118
cp = 0;
119
cr = 1.0f;
120
} else {
121
cp = safe_sqrt(1 - cx2);
122
cr = rot.c.z / cp;
123
}
124
cp = constrain_float(cp, 0.0f, 1.0f);
125
cr = constrain_float(cr, -1.0f, 1.0f); // this relies on constrain_float() of infinity doing the right thing
126
127
sp = -rot.c.x;
128
129
if (!is_zero(cp)) {
130
sr = rot.c.y / cp;
131
}
132
133
if (is_zero(cp) || isinf(cr) || isnan(cr) || isinf(sr) || isnan(sr)) {
134
float r, p, y;
135
rot.to_euler(&r, &p, &y);
136
cr = cosf(r);
137
sr = sinf(r);
138
}
139
}
140
141
// update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude
142
// should be called after _dcm_matrix is updated
143
void AP_AHRS::update_trig(void)
144
{
145
calc_trig(get_rotation_body_to_ned(),
146
_cos_roll, _cos_pitch, _cos_yaw,
147
_sin_roll, _sin_pitch, _sin_yaw);
148
}
149
150
/*
151
update the centi-degree values
152
*/
153
void AP_AHRS::update_cd_values(void)
154
{
155
roll_sensor = degrees(roll) * 100;
156
pitch_sensor = degrees(pitch) * 100;
157
yaw_sensor = degrees(yaw) * 100;
158
if (yaw_sensor < 0)
159
yaw_sensor += 36000;
160
161
rpy_deg[0] = degrees(roll);
162
rpy_deg[1] = degrees(pitch);
163
rpy_deg[2] = wrap_360(degrees(yaw)); // we are probably already in trouble if this is required
164
}
165
166
/*
167
create a rotated view of AP_AHRS with optional pitch trim
168
*/
169
AP_AHRS_View *AP_AHRS::create_view(enum Rotation rotation, float pitch_trim_deg)
170
{
171
if (_view != nullptr) {
172
// can only have one
173
return nullptr;
174
}
175
_view = NEW_NOTHROW AP_AHRS_View(*this, rotation, pitch_trim_deg);
176
return _view;
177
}
178
179
/*
180
* Update AOA and SSA estimation based on airspeed, velocity vector and wind vector
181
*
182
* Based on:
183
* "On estimation of wind velocity, angle-of-attack and sideslip angle of small UAVs using standard sensors" by
184
* Tor A. Johansen, Andrea Cristofaro, Kim Sorensen, Jakob M. Hansen, Thor I. Fossen
185
*
186
* "Multi-Stage Fusion Algorithm for Estimation of Aerodynamic Angles in Mini Aerial Vehicle" by
187
* C.Ramprasadh and Hemendra Arya
188
*
189
* "ANGLE OF ATTACK AND SIDESLIP ESTIMATION USING AN INERTIAL REFERENCE PLATFORM" by
190
* JOSEPH E. ZEIS, JR., CAPTAIN, USAF
191
*/
192
void AP_AHRS::update_AOA_SSA(void)
193
{
194
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
195
const uint32_t now = AP_HAL::millis();
196
if (now - _last_AOA_update_ms < 50) {
197
// don't update at more than 20Hz
198
return;
199
}
200
_last_AOA_update_ms = now;
201
202
Vector3f aoa_velocity, aoa_wind;
203
204
// get velocity and wind
205
if (get_velocity_NED(aoa_velocity) == false) {
206
return;
207
}
208
209
aoa_wind = wind_estimate();
210
211
// Rotate vectors to the body frame and calculate velocity and wind
212
const Matrix3f &rot = get_rotation_body_to_ned();
213
aoa_velocity = rot.mul_transpose(aoa_velocity);
214
aoa_wind = rot.mul_transpose(aoa_wind);
215
216
// calculate relative velocity in body coordinates
217
aoa_velocity = aoa_velocity - aoa_wind;
218
const float vel_len = aoa_velocity.length();
219
220
// do not calculate if speed is too low
221
if (vel_len < 2.0) {
222
_AOA = 0;
223
_SSA = 0;
224
return;
225
}
226
227
// Calculate AOA and SSA
228
if (aoa_velocity.x > 0) {
229
_AOA = degrees(atanf(aoa_velocity.z / aoa_velocity.x));
230
} else {
231
_AOA = 0;
232
}
233
234
_SSA = degrees(safe_asin(aoa_velocity.y / vel_len));
235
#endif
236
}
237
238
// rotate a 2D vector from earth frame to body frame
239
Vector2f AP_AHRS::earth_to_body2D(const Vector2f &ef) const
240
{
241
return Vector2f(ef.x * _cos_yaw + ef.y * _sin_yaw,
242
-ef.x * _sin_yaw + ef.y * _cos_yaw);
243
}
244
245
// rotate a 2D vector from earth frame to body frame
246
Vector2f AP_AHRS::body_to_earth2D(const Vector2f &bf) const
247
{
248
return Vector2f(bf.x * _cos_yaw - bf.y * _sin_yaw,
249
bf.x * _sin_yaw + bf.y * _cos_yaw);
250
}
251
252
// rotate a 2D vector from earth frame to body frame
253
Vector2p AP_AHRS::body_to_earth2D_p(const Vector2p &bf) const
254
{
255
return Vector2p(bf.x * _cos_yaw - bf.y * _sin_yaw,
256
bf.x * _sin_yaw + bf.y * _cos_yaw);
257
}
258
259
#if HAL_LOGGING_ENABLED
260
// log ahrs home and EKF origin
261
void AP_AHRS::Log_Write_Home_And_Origin()
262
{
263
AP_Logger *logger = AP_Logger::get_singleton();
264
if (logger == nullptr) {
265
return;
266
}
267
Location ekf_orig;
268
if (get_origin(ekf_orig)) {
269
Write_Origin(LogOriginType::ekf_origin, ekf_orig);
270
}
271
272
if (_home_is_set) {
273
Write_Origin(LogOriginType::ahrs_home, _home);
274
}
275
}
276
#endif
277
278
// get apparent to true airspeed ratio
279
float AP_AHRS_Backend::get_EAS2TAS(void) {
280
return AP::baro()._get_EAS2TAS();
281
}
282
283
// return current vibration vector for primary IMU
284
Vector3f AP_AHRS::get_vibration(void) const
285
{
286
return AP::ins().get_vibration_levels();
287
}
288
289
void AP_AHRS::set_takeoff_expected(bool b)
290
{
291
takeoff_expected = b;
292
takeoff_expected_start_ms = AP_HAL::millis();
293
}
294
295
void AP_AHRS::set_touchdown_expected(bool b)
296
{
297
touchdown_expected = b;
298
touchdown_expected_start_ms = AP_HAL::millis();
299
}
300
301
/*
302
update takeoff/touchdown flags
303
*/
304
void AP_AHRS::update_flags(void)
305
{
306
const uint32_t timeout_ms = 1000;
307
if (takeoff_expected && AP_HAL::millis() - takeoff_expected_start_ms > timeout_ms) {
308
takeoff_expected = false;
309
}
310
if (touchdown_expected && AP_HAL::millis() - touchdown_expected_start_ms > timeout_ms) {
311
touchdown_expected = false;
312
}
313
}
314
315