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_Backend.cpp
Views: 1798
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, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT)),
46
constrain_float(new_trim.y, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT)),
47
constrain_float(new_trim.z, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(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, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(AP_AHRS_TRIM_LIMIT));
59
trim.y = constrain_float(trim.y + pitch_in_radians, ToRad(-AP_AHRS_TRIM_LIMIT), ToRad(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 (now_ms - last_orientation_update_ms < 1000) {
75
// only update once/second
76
return;
77
}
78
79
// never update while armed - unless we've never updated
80
// (e.g. mid-air reboot or ARMING_REQUIRED=NO on Plane):
81
if (hal.util->get_soft_armed() && last_orientation_update_ms != 0) {
82
return;
83
}
84
85
last_orientation_update_ms = now_ms;
86
87
const enum Rotation orientation = (enum Rotation)_board_orientation.get();
88
89
AP::ins().set_board_orientation(orientation);
90
AP::compass().set_board_orientation(orientation);
91
}
92
93
/*
94
calculate sin and cos of roll/pitch/yaw from a body_to_ned rotation matrix
95
*/
96
void AP_AHRS::calc_trig(const Matrix3f &rot,
97
float &cr, float &cp, float &cy,
98
float &sr, float &sp, float &sy) const
99
{
100
Vector2f yaw_vector(rot.a.x, rot.b.x);
101
102
if (fabsf(yaw_vector.x) > 0 ||
103
fabsf(yaw_vector.y) > 0) {
104
yaw_vector.normalize();
105
}
106
sy = constrain_float(yaw_vector.y, -1.0f, 1.0f);
107
cy = constrain_float(yaw_vector.x, -1.0f, 1.0f);
108
109
// sanity checks
110
if (yaw_vector.is_inf() || yaw_vector.is_nan()) {
111
sy = 0.0f;
112
cy = 1.0f;
113
}
114
115
const float cx2 = rot.c.x * rot.c.x;
116
if (cx2 >= 1.0f) {
117
cp = 0;
118
cr = 1.0f;
119
} else {
120
cp = safe_sqrt(1 - cx2);
121
cr = rot.c.z / cp;
122
}
123
cp = constrain_float(cp, 0.0f, 1.0f);
124
cr = constrain_float(cr, -1.0f, 1.0f); // this relies on constrain_float() of infinity doing the right thing
125
126
sp = -rot.c.x;
127
128
if (!is_zero(cp)) {
129
sr = rot.c.y / cp;
130
}
131
132
if (is_zero(cp) || isinf(cr) || isnan(cr) || isinf(sr) || isnan(sr)) {
133
float r, p, y;
134
rot.to_euler(&r, &p, &y);
135
cr = cosf(r);
136
sr = sinf(r);
137
}
138
}
139
140
// update_trig - recalculates _cos_roll, _cos_pitch, etc based on latest attitude
141
// should be called after _dcm_matrix is updated
142
void AP_AHRS::update_trig(void)
143
{
144
calc_trig(get_rotation_body_to_ned(),
145
_cos_roll, _cos_pitch, _cos_yaw,
146
_sin_roll, _sin_pitch, _sin_yaw);
147
}
148
149
/*
150
update the centi-degree values
151
*/
152
void AP_AHRS::update_cd_values(void)
153
{
154
roll_sensor = degrees(roll) * 100;
155
pitch_sensor = degrees(pitch) * 100;
156
yaw_sensor = degrees(yaw) * 100;
157
if (yaw_sensor < 0)
158
yaw_sensor += 36000;
159
}
160
161
/*
162
create a rotated view of AP_AHRS with optional pitch trim
163
*/
164
AP_AHRS_View *AP_AHRS::create_view(enum Rotation rotation, float pitch_trim_deg)
165
{
166
if (_view != nullptr) {
167
// can only have one
168
return nullptr;
169
}
170
_view = NEW_NOTHROW AP_AHRS_View(*this, rotation, pitch_trim_deg);
171
return _view;
172
}
173
174
/*
175
* Update AOA and SSA estimation based on airspeed, velocity vector and wind vector
176
*
177
* Based on:
178
* "On estimation of wind velocity, angle-of-attack and sideslip angle of small UAVs using standard sensors" by
179
* Tor A. Johansen, Andrea Cristofaro, Kim Sorensen, Jakob M. Hansen, Thor I. Fossen
180
*
181
* "Multi-Stage Fusion Algorithm for Estimation of Aerodynamic Angles in Mini Aerial Vehicle" by
182
* C.Ramprasadh and Hemendra Arya
183
*
184
* "ANGLE OF ATTACK AND SIDESLIP ESTIMATION USING AN INERTIAL REFERENCE PLATFORM" by
185
* JOSEPH E. ZEIS, JR., CAPTAIN, USAF
186
*/
187
void AP_AHRS::update_AOA_SSA(void)
188
{
189
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
190
const uint32_t now = AP_HAL::millis();
191
if (now - _last_AOA_update_ms < 50) {
192
// don't update at more than 20Hz
193
return;
194
}
195
_last_AOA_update_ms = now;
196
197
Vector3f aoa_velocity, aoa_wind;
198
199
// get velocity and wind
200
if (get_velocity_NED(aoa_velocity) == false) {
201
return;
202
}
203
204
aoa_wind = wind_estimate();
205
206
// Rotate vectors to the body frame and calculate velocity and wind
207
const Matrix3f &rot = get_rotation_body_to_ned();
208
aoa_velocity = rot.mul_transpose(aoa_velocity);
209
aoa_wind = rot.mul_transpose(aoa_wind);
210
211
// calculate relative velocity in body coordinates
212
aoa_velocity = aoa_velocity - aoa_wind;
213
const float vel_len = aoa_velocity.length();
214
215
// do not calculate if speed is too low
216
if (vel_len < 2.0) {
217
_AOA = 0;
218
_SSA = 0;
219
return;
220
}
221
222
// Calculate AOA and SSA
223
if (aoa_velocity.x > 0) {
224
_AOA = degrees(atanf(aoa_velocity.z / aoa_velocity.x));
225
} else {
226
_AOA = 0;
227
}
228
229
_SSA = degrees(safe_asin(aoa_velocity.y / vel_len));
230
#endif
231
}
232
233
// rotate a 2D vector from earth frame to body frame
234
Vector2f AP_AHRS::earth_to_body2D(const Vector2f &ef) const
235
{
236
return Vector2f(ef.x * _cos_yaw + ef.y * _sin_yaw,
237
-ef.x * _sin_yaw + ef.y * _cos_yaw);
238
}
239
240
// rotate a 2D vector from earth frame to body frame
241
Vector2f AP_AHRS::body_to_earth2D(const Vector2f &bf) const
242
{
243
return Vector2f(bf.x * _cos_yaw - bf.y * _sin_yaw,
244
bf.x * _sin_yaw + bf.y * _cos_yaw);
245
}
246
247
#if HAL_LOGGING_ENABLED
248
// log ahrs home and EKF origin
249
void AP_AHRS::Log_Write_Home_And_Origin()
250
{
251
AP_Logger *logger = AP_Logger::get_singleton();
252
if (logger == nullptr) {
253
return;
254
}
255
Location ekf_orig;
256
if (get_origin(ekf_orig)) {
257
Write_Origin(LogOriginType::ekf_origin, ekf_orig);
258
}
259
260
if (_home_is_set) {
261
Write_Origin(LogOriginType::ahrs_home, _home);
262
}
263
}
264
#endif
265
266
// get apparent to true airspeed ratio
267
float AP_AHRS_Backend::get_EAS2TAS(void) {
268
return AP::baro()._get_EAS2TAS();
269
}
270
271
// return current vibration vector for primary IMU
272
Vector3f AP_AHRS::get_vibration(void) const
273
{
274
return AP::ins().get_vibration_levels();
275
}
276
277
void AP_AHRS::set_takeoff_expected(bool b)
278
{
279
takeoff_expected = b;
280
takeoff_expected_start_ms = AP_HAL::millis();
281
}
282
283
void AP_AHRS::set_touchdown_expected(bool b)
284
{
285
touchdown_expected = b;
286
touchdown_expected_start_ms = AP_HAL::millis();
287
}
288
289
/*
290
update takeoff/touchdown flags
291
*/
292
void AP_AHRS::update_flags(void)
293
{
294
const uint32_t timeout_ms = 1000;
295
if (takeoff_expected && AP_HAL::millis() - takeoff_expected_start_ms > timeout_ms) {
296
takeoff_expected = false;
297
}
298
if (touchdown_expected && AP_HAL::millis() - touchdown_expected_start_ms > timeout_ms) {
299
touchdown_expected = false;
300
}
301
}
302
303