Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_AHRS/AP_AHRS_SIM.cpp
9449 views
1
#include "AP_AHRS_SIM.h"
2
3
#if AP_AHRS_SIM_ENABLED
4
5
#include "AP_AHRS.h"
6
7
bool AP_AHRS_SIM::get_location(Location &loc) const
8
{
9
if (_sitl == nullptr) {
10
return false;
11
}
12
13
const struct SITL::sitl_fdm &fdm = _sitl->state;
14
loc = {};
15
loc.lat = fdm.latitude * 1e7;
16
loc.lng = fdm.longitude * 1e7;
17
loc.alt = fdm.altitude*100;
18
19
return true;
20
}
21
22
bool AP_AHRS_SIM::wind_estimate(Vector3f &wind) const
23
{
24
if (_sitl == nullptr) {
25
return false;
26
}
27
28
wind = _sitl->state.wind_ef;
29
return true;
30
}
31
32
bool AP_AHRS_SIM::airspeed_EAS(float &airspeed_ret) const
33
{
34
if (_sitl == nullptr) {
35
return false;
36
}
37
38
airspeed_ret = _sitl->state.airspeed;
39
40
return true;
41
}
42
43
bool AP_AHRS_SIM::airspeed_EAS(uint8_t index, float &airspeed_ret) const
44
{
45
return airspeed_EAS(airspeed_ret);
46
}
47
48
Vector2f AP_AHRS_SIM::groundspeed_vector(void)
49
{
50
if (_sitl == nullptr) {
51
return Vector2f{};
52
}
53
54
const struct SITL::sitl_fdm &fdm = _sitl->state;
55
56
return Vector2f(fdm.speedN, fdm.speedE);
57
}
58
59
bool AP_AHRS_SIM::get_hagl(float &height) const
60
{
61
if (_sitl == nullptr) {
62
return false;
63
}
64
65
height = _sitl->state.altitude - AP::ahrs().get_home().alt*0.01f;
66
67
return true;
68
}
69
70
bool AP_AHRS_SIM::get_relative_position_NED_origin(Vector3p &vec) const
71
{
72
if (_sitl == nullptr) {
73
return false;
74
}
75
76
Location loc, orgn;
77
if (!get_location(loc) ||
78
!get_origin(orgn)) {
79
return false;
80
}
81
82
const Vector2p diff2d = orgn.get_distance_NE_postype(loc);
83
const struct SITL::sitl_fdm &fdm = _sitl->state;
84
vec = Vector3p(diff2d.x, diff2d.y,
85
-(fdm.altitude - orgn.alt*0.01f));
86
87
return true;
88
}
89
90
bool AP_AHRS_SIM::get_relative_position_NE_origin(Vector2p &posNE) const
91
{
92
Location loc, orgn;
93
if (!get_location(loc) ||
94
!get_origin(orgn)) {
95
return false;
96
}
97
posNE = orgn.get_distance_NE_postype(loc);
98
99
return true;
100
}
101
102
bool AP_AHRS_SIM::get_relative_position_D_origin(postype_t &posD) const
103
{
104
if (_sitl == nullptr) {
105
return false;
106
}
107
const struct SITL::sitl_fdm &fdm = _sitl->state;
108
Location orgn;
109
if (!get_origin(orgn)) {
110
return false;
111
}
112
posD = -(fdm.altitude - orgn.alt*0.01f);
113
114
return true;
115
}
116
117
bool AP_AHRS_SIM::get_filter_status(nav_filter_status &status) const
118
{
119
memset(&status, 0, sizeof(status));
120
status.flags.attitude = true;
121
status.flags.horiz_vel = true;
122
status.flags.vert_vel = true;
123
status.flags.horiz_pos_rel = true;
124
status.flags.horiz_pos_abs = true;
125
status.flags.vert_pos = true;
126
status.flags.pred_horiz_pos_rel = true;
127
status.flags.pred_horiz_pos_abs = true;
128
status.flags.using_gps = true;
129
130
return true;
131
}
132
133
void AP_AHRS_SIM::get_control_limits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
134
{
135
// same as EKF2 for no optical flow
136
ekfGndSpdLimit = 400.0f;
137
ekfNavVelGainScaler = 1.0f;
138
}
139
140
void AP_AHRS_SIM::send_ekf_status_report(GCS_MAVLINK &link) const
141
{
142
#if HAL_GCS_ENABLED
143
// send status report with everything looking good
144
const uint16_t flags =
145
EKF_ATTITUDE | /* Set if EKF's attitude estimate is good. | */
146
EKF_VELOCITY_HORIZ | /* Set if EKF's horizontal velocity estimate is good. | */
147
EKF_VELOCITY_VERT | /* Set if EKF's vertical velocity estimate is good. | */
148
EKF_POS_HORIZ_REL | /* Set if EKF's horizontal position (relative) estimate is good. | */
149
EKF_POS_HORIZ_ABS | /* Set if EKF's horizontal position (absolute) estimate is good. | */
150
EKF_POS_VERT_ABS | /* Set if EKF's vertical position (absolute) estimate is good. | */
151
EKF_POS_VERT_AGL | /* Set if EKF's vertical position (above ground) estimate is good. | */
152
//EKF_CONST_POS_MODE | /* EKF is in constant position mode and does not know it's absolute or relative position. | */
153
EKF_PRED_POS_HORIZ_REL | /* Set if EKF's predicted horizontal position (relative) estimate is good. | */
154
EKF_PRED_POS_HORIZ_ABS; /* Set if EKF's predicted horizontal position (absolute) estimate is good. | */
155
mavlink_msg_ekf_status_report_send(link.get_chan(), flags, 0, 0, 0, 0, 0, 0);
156
#endif // HAL_GCS_ENABLED
157
}
158
159
bool AP_AHRS_SIM::get_origin(Location &ret) const
160
{
161
if (_sitl == nullptr) {
162
return false;
163
}
164
165
ret = _sitl->state.home;
166
167
return true;
168
}
169
170
// return the innovations for the specified instance
171
// An out of range instance (eg -1) returns data for the primary instance
172
bool AP_AHRS_SIM::get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
173
{
174
velInnov.zero();
175
posInnov.zero();
176
magInnov.zero();
177
tasInnov = 0.0f;
178
yawInnov = 0.0f;
179
180
return true;
181
}
182
183
bool AP_AHRS_SIM::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const
184
{
185
velVar = 0;
186
posVar = 0;
187
hgtVar = 0;
188
magVar.zero();
189
tasVar = 0;
190
191
return true;
192
}
193
194
void AP_AHRS_SIM::get_results(AP_AHRS_Backend::Estimates &results)
195
{
196
if (_sitl == nullptr) {
197
_sitl = AP::sitl();
198
if (_sitl == nullptr) {
199
return;
200
}
201
}
202
203
const struct SITL::sitl_fdm &fdm = _sitl->state;
204
const AP_InertialSensor &_ins = AP::ins();
205
206
results.attitude_valid = true;
207
208
// note that this result is rotated by AP_AHRS::get_quaternion
209
results.quaternion = fdm.quaternion;
210
211
fdm.quaternion.rotation_matrix(results.dcm_matrix);
212
results.dcm_matrix = results.dcm_matrix * AP::ahrs().get_rotation_vehicle_body_to_autopilot_body();
213
results.dcm_matrix.to_euler(&results.roll_rad, &results.pitch_rad, &results.yaw_rad);
214
215
results.gyro_estimate = _ins.get_gyro();
216
results.gyro_drift.zero();
217
218
const Vector3f &accel = _ins.get_accel();
219
results.accel_ef = results.dcm_matrix * AP::ahrs().get_rotation_autopilot_body_to_vehicle_body() * accel;
220
221
results.velocity_NED = Vector3f(fdm.speedN, fdm.speedE, fdm.speedD);
222
results.velocity_NED_valid = true;
223
224
// a derivative of the vertical position in m/s which is kinematically consistent with the vertical position is required by some control loops.
225
// 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.
226
results.vert_pos_rate_D_valid = true;
227
results.vert_pos_rate_D = _sitl->state.speedD;
228
229
results.location_valid = get_location(results.location);
230
231
#if HAL_NAVEKF3_AVAILABLE
232
if (_sitl->odom_enable) {
233
// use SITL states to write body frame odometry data at 20Hz
234
uint32_t timeStamp_ms = AP_HAL::millis();
235
if (timeStamp_ms - _last_body_odm_update_ms > 50) {
236
const float quality = 100.0f;
237
const Vector3f posOffset(0.0f, 0.0f, 0.0f);
238
const float delTime = 0.001f * (timeStamp_ms - _last_body_odm_update_ms);
239
_last_body_odm_update_ms = timeStamp_ms;
240
timeStamp_ms -= (timeStamp_ms - _last_body_odm_update_ms)/2; // correct for first order hold average delay
241
Vector3f delAng = _ins.get_gyro();
242
243
delAng *= delTime;
244
// rotate earth velocity into body frame and calculate delta position
245
Matrix3f Tbn;
246
Tbn.from_euler(radians(fdm.rollDeg),radians(fdm.pitchDeg),radians(fdm.yawDeg));
247
const Vector3f earth_vel(fdm.speedN,fdm.speedE,fdm.speedD);
248
const Vector3f delPos = Tbn.transposed() * (earth_vel * delTime);
249
// write to EKF
250
EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, 0, posOffset);
251
}
252
}
253
#endif // HAL_NAVEKF3_AVAILABLE
254
}
255
256
#endif // AP_AHRS_SIM_ENABLED
257
258