Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_AHRS/AP_AHRS_External.cpp
9531 views
1
#include "AP_AHRS_External.h"
2
3
#if AP_AHRS_EXTERNAL_ENABLED
4
5
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
6
#include <AP_AHRS/AP_AHRS.h>
7
8
// true if the AHRS has completed initialisation
9
bool AP_AHRS_External::initialised(void) const
10
{
11
return AP::externalAHRS().initialised();
12
}
13
14
void AP_AHRS_External::update()
15
{
16
AP::externalAHRS().update();
17
}
18
19
bool AP_AHRS_External::healthy() const {
20
return AP::externalAHRS().healthy();
21
}
22
23
void AP_AHRS_External::get_results(AP_AHRS_Backend::Estimates &results)
24
{
25
auto &extahrs = AP::externalAHRS();
26
const AP_InertialSensor &_ins = AP::ins();
27
if (!extahrs.get_quaternion(results.quaternion)) {
28
results.attitude_valid = false;
29
return;
30
}
31
results.attitude_valid = true;
32
results.quaternion.rotation_matrix(results.dcm_matrix);
33
// note that this is suspect; we are rotating the matrix and
34
// eulers away from alignment with the quaternion:
35
results.dcm_matrix = results.dcm_matrix * AP::ahrs().get_rotation_vehicle_body_to_autopilot_body();
36
results.dcm_matrix.to_euler(&results.roll_rad, &results.pitch_rad, &results.yaw_rad);
37
38
results.gyro_drift.zero();
39
if (!extahrs.get_gyro(results.gyro_estimate)) {
40
results.gyro_estimate = _ins.get_gyro();
41
}
42
43
Vector3f accel;
44
if (!extahrs.get_accel(accel)) {
45
accel = _ins.get_accel();
46
}
47
48
const Vector3f accel_ef = results.dcm_matrix * AP::ahrs().get_rotation_autopilot_body_to_vehicle_body() * accel;
49
results.accel_ef = accel_ef;
50
51
results.velocity_NED_valid = AP::externalAHRS().get_velocity_NED(results.velocity_NED);
52
// a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.
53
// This is different to the vertical velocity from the EKF which is not always consistent with the vertical position due to the various errors that are being corrected for.
54
results.vert_pos_rate_D_valid = AP::externalAHRS().get_speed_down(results.vert_pos_rate_D);
55
56
57
results.location_valid = AP::externalAHRS().get_location(results.location);
58
}
59
60
Vector2f AP_AHRS_External::groundspeed_vector()
61
{
62
return AP::externalAHRS().get_groundspeed_vector();
63
}
64
65
66
bool AP_AHRS_External::get_relative_position_NED_origin(Vector3p &vec) const
67
{
68
auto &extahrs = AP::externalAHRS();
69
Location loc, orgn;
70
if (extahrs.get_origin(orgn) &&
71
extahrs.get_location(loc)) {
72
const Vector2f diff2d = orgn.get_distance_NE(loc);
73
vec = Vector3p(diff2d.x, diff2d.y,
74
-(loc.alt - orgn.alt)*0.01);
75
return true;
76
}
77
return false;
78
}
79
80
bool AP_AHRS_External::get_relative_position_NE_origin(Vector2p &posNE) const
81
{
82
auto &extahrs = AP::externalAHRS();
83
84
Location loc, orgn;
85
if (!extahrs.get_location(loc) ||
86
!extahrs.get_origin(orgn)) {
87
return false;
88
}
89
posNE = orgn.get_distance_NE_postype(loc);
90
return true;
91
}
92
93
bool AP_AHRS_External::get_relative_position_D_origin(postype_t &posD) const
94
{
95
auto &extahrs = AP::externalAHRS();
96
97
Location orgn, loc;
98
if (!extahrs.get_origin(orgn) ||
99
!extahrs.get_location(loc)) {
100
return false;
101
}
102
posD = -(loc.alt - orgn.alt)*0.01;
103
return true;
104
}
105
106
bool AP_AHRS_External::pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const
107
{
108
return AP::externalAHRS().pre_arm_check(failure_msg, failure_msg_len);
109
}
110
111
bool AP_AHRS_External::get_filter_status(nav_filter_status &status) const
112
{
113
AP::externalAHRS().get_filter_status(status);
114
return true;
115
}
116
117
void AP_AHRS_External::send_ekf_status_report(GCS_MAVLINK &link) const
118
{
119
AP::externalAHRS().send_status_report(link);
120
}
121
122
bool AP_AHRS_External::get_origin(Location &ret) const
123
{
124
return AP::externalAHRS().get_origin(ret);
125
}
126
127
void AP_AHRS_External::get_control_limits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
128
{
129
// lower gains in VTOL controllers when flying on DCM
130
ekfGndSpdLimit = 50.0;
131
ekfNavVelGainScaler = 0.5;
132
}
133
134
#endif
135
136