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_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
This program is distributed in the hope that it will be useful,
7
but WITHOUT ANY WARRANTY; without even the implied warranty of
8
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
9
GNU General Public License for more details.
10
You should have received a copy of the GNU General Public License
11
along with this program. If not, see <http://www.gnu.org/licenses/>.
12
*/
13
/*
14
support for MicroStrain CX5/GX5-45 serially connected AHRS Systems
15
*/
16
17
#define ALLOW_DOUBLE_MATH_FUNCTIONS
18
19
#include "AP_ExternalAHRS_config.h"
20
21
#if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED
22
23
#include "AP_ExternalAHRS_MicroStrain5.h"
24
#include "AP_Compass/AP_Compass_config.h"
25
#include <AP_Baro/AP_Baro.h>
26
#include <AP_Compass/AP_Compass.h>
27
#include <AP_GPS/AP_GPS.h>
28
#include <AP_HAL/utility/sparse-endian.h>
29
#include <AP_InertialSensor/AP_InertialSensor.h>
30
#include <GCS_MAVLink/GCS.h>
31
#include <AP_Logger/AP_Logger.h>
32
#include <AP_BoardConfig/AP_BoardConfig.h>
33
#include <AP_SerialManager/AP_SerialManager.h>
34
35
extern const AP_HAL::HAL &hal;
36
37
static constexpr uint8_t gnss_instance = 0;
38
39
AP_ExternalAHRS_MicroStrain5::AP_ExternalAHRS_MicroStrain5(AP_ExternalAHRS *_frontend,
40
AP_ExternalAHRS::state_t &_state): AP_ExternalAHRS_backend(_frontend, _state)
41
{
42
auto &sm = AP::serialmanager();
43
uart = sm.find_serial(AP_SerialManager::SerialProtocol_AHRS, 0);
44
45
baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0);
46
port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0);
47
48
if (!uart) {
49
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "MicroStrain5 ExternalAHRS no UART");
50
return;
51
}
52
53
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_MicroStrain5::update_thread, void), "AHRS", 2048, AP_HAL::Scheduler::PRIORITY_SPI, 0)) {
54
AP_BoardConfig::allocation_error("MicroStrain5 failed to allocate ExternalAHRS update thread");
55
}
56
57
hal.scheduler->delay(5000);
58
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MicroStrain5 ExternalAHRS initialised");
59
}
60
61
void AP_ExternalAHRS_MicroStrain5::update_thread(void)
62
{
63
if (!port_open) {
64
port_open = true;
65
uart->begin(baudrate);
66
}
67
68
while (true) {
69
build_packet();
70
hal.scheduler->delay_microseconds(100);
71
}
72
}
73
74
75
76
// Builds packets by looking at each individual byte, once a full packet has been read in it checks the checksum then handles the packet.
77
void AP_ExternalAHRS_MicroStrain5::build_packet()
78
{
79
if (uart == nullptr) {
80
return;
81
}
82
83
WITH_SEMAPHORE(sem);
84
uint32_t nbytes = MIN(uart->available(), 2048u);
85
while (nbytes--> 0) {
86
uint8_t b;
87
if (!uart->read(b)) {
88
break;
89
}
90
DescriptorSet descriptor;
91
if (handle_byte(b, descriptor)) {
92
switch (descriptor) {
93
case DescriptorSet::IMUData:
94
post_imu();
95
break;
96
case DescriptorSet::GNSSData:
97
case DescriptorSet::GNSSRecv1:
98
case DescriptorSet::GNSSRecv2:
99
break;
100
case DescriptorSet::FilterData:
101
post_filter();
102
break;
103
case DescriptorSet::BaseCommand:
104
case DescriptorSet::DMCommand:
105
case DescriptorSet::SystemCommand:
106
break;
107
}
108
}
109
}
110
}
111
112
113
114
// Posts data from an imu packet to `state` and `handle_external` methods
115
void AP_ExternalAHRS_MicroStrain5::post_imu() const
116
{
117
{
118
WITH_SEMAPHORE(state.sem);
119
state.accel = imu_data.accel;
120
state.gyro = imu_data.gyro;
121
122
state.quat = imu_data.quat;
123
state.have_quaternion = true;
124
}
125
126
{
127
AP_ExternalAHRS::ins_data_message_t ins {
128
accel: imu_data.accel,
129
gyro: imu_data.gyro,
130
temperature: -300
131
};
132
AP::ins().handle_external(ins);
133
}
134
135
#if AP_COMPASS_EXTERNALAHRS_ENABLED
136
{
137
AP_ExternalAHRS::mag_data_message_t mag {
138
field: imu_data.mag
139
};
140
AP::compass().handle_external(mag);
141
}
142
#endif
143
144
#if AP_BARO_EXTERNALAHRS_ENABLED
145
{
146
const AP_ExternalAHRS::baro_data_message_t baro {
147
instance: 0,
148
pressure_pa: imu_data.pressure,
149
// setting temp to 25 effectively disables barometer temperature calibrations - these are already performed by MicroStrain
150
temperature: 25,
151
};
152
AP::baro().handle_external(baro);
153
}
154
#endif
155
}
156
157
void AP_ExternalAHRS_MicroStrain5::post_filter() const
158
{
159
{
160
WITH_SEMAPHORE(state.sem);
161
state.velocity = Vector3f{filter_data.ned_velocity_north, filter_data.ned_velocity_east, filter_data.ned_velocity_down};
162
state.have_velocity = true;
163
164
state.location = Location{filter_data.lat, filter_data.lon, gnss_data[gnss_instance].msl_altitude, Location::AltFrame::ABSOLUTE};
165
state.have_location = true;
166
state.last_location_update_us = AP_HAL::micros();
167
}
168
169
AP_ExternalAHRS::gps_data_message_t gps {
170
gps_week: filter_data.week,
171
ms_tow: filter_data.tow_ms,
172
fix_type: AP_GPS_FixType(gnss_data[gnss_instance].fix_type),
173
satellites_in_view: gnss_data[gnss_instance].satellites,
174
175
horizontal_pos_accuracy: gnss_data[gnss_instance].horizontal_position_accuracy,
176
vertical_pos_accuracy: gnss_data[gnss_instance].vertical_position_accuracy,
177
horizontal_vel_accuracy: gnss_data[gnss_instance].speed_accuracy,
178
179
hdop: gnss_data[gnss_instance].hdop,
180
vdop: gnss_data[gnss_instance].vdop,
181
182
longitude: filter_data.lon,
183
latitude: filter_data.lat,
184
msl_altitude: gnss_data[gnss_instance].msl_altitude,
185
186
ned_vel_north: filter_data.ned_velocity_north,
187
ned_vel_east: filter_data.ned_velocity_east,
188
ned_vel_down: filter_data.ned_velocity_down,
189
};
190
191
if (gps.fix_type >= AP_GPS_FixType::FIX_3D && !state.have_origin) {
192
WITH_SEMAPHORE(state.sem);
193
state.origin = Location{int32_t(filter_data.lat),
194
int32_t(filter_data.lon),
195
int32_t(gnss_data[gnss_instance].msl_altitude),
196
Location::AltFrame::ABSOLUTE};
197
state.have_origin = true;
198
}
199
200
uint8_t gps_instance;
201
if (AP::gps().get_first_external_instance(gps_instance)) {
202
AP::gps().handle_external(gps, gps_instance);
203
}
204
}
205
206
int8_t AP_ExternalAHRS_MicroStrain5::get_port(void) const
207
{
208
if (!uart) {
209
return -1;
210
}
211
return port_num;
212
};
213
214
// Get model/type name
215
const char* AP_ExternalAHRS_MicroStrain5::get_name() const
216
{
217
return "MicroStrain5";
218
}
219
220
bool AP_ExternalAHRS_MicroStrain5::healthy(void) const
221
{
222
uint32_t now = AP_HAL::millis();
223
return (now - last_imu_pkt < 40 && now - last_gps_pkt < 500 && now - last_filter_pkt < 500);
224
}
225
226
bool AP_ExternalAHRS_MicroStrain5::initialised(void) const
227
{
228
return last_imu_pkt != 0 && last_gps_pkt != 0 && last_filter_pkt != 0;
229
}
230
231
bool AP_ExternalAHRS_MicroStrain5::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const
232
{
233
if (!healthy()) {
234
hal.util->snprintf(failure_msg, failure_msg_len, "MicroStrain5 unhealthy");
235
return false;
236
}
237
if (gnss_data[gnss_instance].fix_type < 3) {
238
hal.util->snprintf(failure_msg, failure_msg_len, "MicroStrain5 no GPS lock");
239
return false;
240
}
241
if (filter_status.state != 0x02) {
242
hal.util->snprintf(failure_msg, failure_msg_len, "MicroStrain5 filter not running");
243
return false;
244
}
245
246
return true;
247
}
248
249
void AP_ExternalAHRS_MicroStrain5::get_filter_status(nav_filter_status &status) const
250
{
251
memset(&status, 0, sizeof(status));
252
if (last_imu_pkt != 0 && last_gps_pkt != 0) {
253
status.flags.initalized = true;
254
}
255
if (healthy() && last_imu_pkt != 0) {
256
status.flags.attitude = true;
257
status.flags.vert_vel = true;
258
status.flags.vert_pos = true;
259
260
if (gnss_data[gnss_instance].fix_type >= 3) {
261
status.flags.horiz_vel = true;
262
status.flags.horiz_pos_rel = true;
263
status.flags.horiz_pos_abs = true;
264
status.flags.pred_horiz_pos_rel = true;
265
status.flags.pred_horiz_pos_abs = true;
266
status.flags.using_gps = true;
267
}
268
}
269
}
270
271
// get variances
272
bool AP_ExternalAHRS_MicroStrain5::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const
273
{
274
velVar = gnss_data[gnss_instance].speed_accuracy * vel_gate_scale;
275
posVar = gnss_data[gnss_instance].horizontal_position_accuracy * pos_gate_scale;
276
hgtVar = gnss_data[gnss_instance].vertical_position_accuracy * hgt_gate_scale;
277
tasVar = 0;
278
return true;
279
}
280
281
282
#endif // AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED
283
284