-
-
Notifications
You must be signed in to change notification settings - Fork 502
/
mission_import.cpp
413 lines (345 loc) · 13.6 KB
/
mission_import.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
#include "log.h"
#include "mission_import.h"
#include "mavlink_include.h"
#include <cmath> // for `std::round`
#include <sstream> // for `std::stringstream`
namespace mavsdk {
std::pair<MissionRaw::Result, MissionRaw::MissionImportData>
MissionImport::parse_json(const std::string& raw_json, Autopilot autopilot)
{
Json::CharReaderBuilder builder;
const std::unique_ptr<Json::CharReader> reader(builder.newCharReader());
Json::Value root;
JSONCPP_STRING err;
if (!reader->parse(raw_json.c_str(), raw_json.c_str() + raw_json.length(), &root, &err)) {
LogErr() << "Parse error: " << err;
return {MissionRaw::Result::FailedToParseQgcPlan, {}};
}
if (!check_overall_version(root)) {
return {MissionRaw::Result::FailedToParseQgcPlan, {}};
}
auto maybe_mission_items = import_mission(root, autopilot);
if (!maybe_mission_items.has_value()) {
return {MissionRaw::Result::FailedToParseQgcPlan, {}};
}
auto maybe_geofence_items = import_geofence(root);
if (!maybe_geofence_items.has_value()) {
return {MissionRaw::Result::FailedToParseQgcPlan, {}};
}
auto maybe_rally_items = import_rally_points(root);
if (!maybe_rally_items.has_value()) {
return {MissionRaw::Result::FailedToParseQgcPlan, {}};
}
MissionRaw::MissionImportData import_data;
import_data.mission_items = maybe_mission_items.value();
import_data.geofence_items = maybe_geofence_items.value();
import_data.rally_items = maybe_rally_items.value();
return {MissionRaw::Result::Success, import_data};
}
bool MissionImport::check_overall_version(const Json::Value& root)
{
const auto supported_overall_version = 1;
const auto overall_version = root["version"];
if (overall_version.empty() || overall_version.asInt() != supported_overall_version) {
LogErr() << "Overall .plan version not supported, found version: " << overall_version
<< ", supported: " << supported_overall_version;
return false;
}
return true;
}
std::optional<std::vector<MissionRaw::MissionItem>>
MissionImport::import_mission(const Json::Value& root, Autopilot autopilot)
{
// We need a mission part.
const auto mission = root["mission"];
if (mission.empty()) {
LogErr() << "No mission found in .plan.";
return std::nullopt;
}
// Check the mission version.
const auto supported_mission_version = 2;
const auto mission_version = mission["version"];
if (mission_version.empty() || mission_version.asInt() != supported_mission_version) {
LogErr() << "mission version for .plan not supported, found version: "
<< mission_version.asInt() << ", supported: " << supported_mission_version;
return std::nullopt;
}
std::vector<MissionRaw::MissionItem> mission_items;
// Go through items
for (const auto& json_item : mission["items"]) {
const auto type = json_item["type"];
if (!type.isNull() && type.asString() == "SimpleItem") {
const auto maybe_item = import_simple_mission_item(json_item);
if (maybe_item.has_value()) {
mission_items.push_back(maybe_item.value());
} else {
return std::nullopt;
}
} else if (!type.isNull() && type.asString() == "ComplexItem") {
const auto maybe_items = import_complex_mission_items(json_item);
if (maybe_items.has_value()) {
mission_items.insert(
mission_items.end(), maybe_items.value().begin(), maybe_items.value().end());
} else {
return std::nullopt;
}
} else {
LogErr() << "Type " << type.asString() << " not understood.";
return std::nullopt;
}
}
// Mark first item as current
if (mission_items.size() > 0) {
mission_items[0].current = 1;
}
// Add home position at 0 for ArduPilot
if (autopilot == Autopilot::ArduPilot) {
const auto home = mission["plannedHomePosition"];
if (!home.empty()) {
if (home.isArray() && home.size() != 3) {
LogErr() << "Unknown plannedHomePosition format";
return std::nullopt;
}
mission_items.insert(
mission_items.begin(),
MissionRaw::MissionItem{
0,
MAV_FRAME_GLOBAL_INT,
MAV_CMD_NAV_WAYPOINT,
0, // current
1, // autocontinue
0.0f,
0.0f,
0.0f,
0.0f,
static_cast<int32_t>(std::round(home[0].asDouble() * 1e7)),
static_cast<int32_t>(std::round(home[1].asDouble() * 1e7)),
home[2].asFloat(),
MAV_MISSION_TYPE_MISSION});
}
}
// Don't forget sequence number
unsigned sequence = 0;
for (auto& mission_item : mission_items) {
mission_item.seq = sequence++;
}
// Returning an empty vector is ok here if there were really no mission items.
return {mission_items};
}
std::optional<std::vector<MissionRaw::MissionItem>>
MissionImport::import_geofence(const Json::Value& root)
{
std::vector<MissionRaw::MissionItem> geofence_items;
// Return early if there are no geofence items.
const auto geofence = root["geoFence"];
if (geofence.empty()) {
return std::nullopt;
}
// Check the mission version.
const auto supported_geofence_version = 2;
const auto geofence_version = geofence["version"];
if (geofence_version.empty() || geofence_version.asInt() != supported_geofence_version) {
LogErr() << "geofence version for .plan not supported, found version: "
<< geofence_version.asInt() << ", supported: " << supported_geofence_version;
return std::nullopt;
}
// Import polygon geofences
std::vector<MissionRaw::MissionItem> polygon_geofences;
polygon_geofences = import_polygon_geofences(geofence["polygons"]);
// Import circular geofences
std::vector<MissionRaw::MissionItem> circular_geofences;
circular_geofences = import_circular_geofences(geofence["circles"]);
geofence_items.insert(geofence_items.end(), polygon_geofences.begin(), polygon_geofences.end());
geofence_items.insert(
geofence_items.end(), circular_geofences.begin(), circular_geofences.end());
// Mark first item as current
if (geofence_items.size() > 0) {
geofence_items[0].current = 1;
}
// Don't forget sequence number
unsigned sequence = 0;
for (auto& item : geofence_items) {
item.seq = sequence++;
}
return {geofence_items};
}
std::optional<std::vector<MissionRaw::MissionItem>>
MissionImport::import_rally_points(const Json::Value& root)
{
std::vector<MissionRaw::MissionItem> rally_items;
// Return early if there are no rally points.
const auto rally_points = root["rallyPoints"];
if (rally_points.empty()) {
return std::nullopt;
}
// Check the rally points version.
const auto supported_rally_points_version = 2;
const auto rally_points_version = rally_points["version"];
if (rally_points_version.empty() ||
rally_points_version.asInt() != supported_rally_points_version) {
LogErr() << "rally points version for .plan not supported, found version: "
<< rally_points_version.asInt()
<< ", supported: " << supported_rally_points_version;
return std::nullopt;
}
// Go through items
for (const auto& point : rally_points["points"]) {
MissionRaw::MissionItem item{};
item.command = MAV_CMD_NAV_RALLY_POINT;
item.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
item.mission_type = MAV_MISSION_TYPE_RALLY;
item.x = set_int32(point[0]);
item.y = set_int32(point[1]);
item.z = set_float(point[2]);
rally_items.push_back(item);
}
// Mark first item as current
if (rally_items.size() > 0) {
rally_items[0].current = 1;
}
// Don't forget sequence number
unsigned sequence = 0;
for (auto& item : rally_items) {
item.seq = sequence++;
}
return {rally_items};
}
std::optional<MissionRaw::MissionItem>
MissionImport::import_simple_mission_item(const Json::Value& json_item)
{
if (json_item["command"].empty() || json_item["autoContinue"].empty() ||
json_item["frame"].empty() || json_item["params"].empty()) {
LogErr() << "Missing mission item field.";
return std::nullopt;
}
if (!json_item["params"].isArray()) {
LogErr() << "No param array found.";
return std::nullopt;
}
MissionRaw::MissionItem item{};
item.command = json_item["command"].asInt();
item.autocontinue = json_item["autoContinue"].asBool() ? 1 : 0;
item.frame = json_item["frame"].asInt();
item.mission_type = MAV_MISSION_TYPE_MISSION;
for (unsigned i = 0; i < 7; ++i) {
switch (i) {
case 0:
item.param1 = set_float(json_item["params"][i]);
break;
case 1:
item.param2 = set_float(json_item["params"][i]);
break;
case 2:
item.param3 = set_float(json_item["params"][i]);
break;
case 3:
item.param4 = set_float(json_item["params"][i]);
break;
case 4:
item.x = set_int32(json_item["params"][i]);
break;
case 5:
item.y = set_int32(json_item["params"][i]);
break;
case 6:
item.z = set_float(json_item["params"][i]);
break;
default:
// should never happen
break;
}
}
return {item};
}
std::optional<std::vector<MissionRaw::MissionItem>>
MissionImport::import_complex_mission_items(const Json::Value& json_item)
{
if (json_item["complexItemType"].empty()) {
LogErr() << "Could not determine complexItemType";
return std::nullopt;
}
if (json_item["complexItemType"] != "survey") {
LogErr() << "complexItemType: " << json_item["complexItemType"] << " not supported";
return std::nullopt;
}
if (json_item["version"].empty()) {
LogErr() << "version of complexItem not found";
return std::nullopt;
}
const int supported_complex_item_version = 5;
const int found_version = json_item["version"].asInt();
if (found_version != 5) {
LogErr() << "version of complexItem not supported, found version: " << found_version
<< ", supported: " << supported_complex_item_version;
return std::nullopt;
}
if (json_item["TransectStyleComplexItem"].empty()) {
LogErr() << "TransectStyleComplexItem not found";
return std::nullopt;
}
// These are Items (capitalized!) inside the TransectStyleComplexItem.
if (json_item["TransectStyleComplexItem"]["Items"].empty() ||
!json_item["TransectStyleComplexItem"]["Items"].isArray()) {
LogErr() << "No survey items found";
return std::nullopt;
}
std::vector<MissionRaw::MissionItem> mission_items;
for (const auto& json_item_subitem : json_item["TransectStyleComplexItem"]["Items"]) {
const auto maybe_item = import_simple_mission_item(json_item_subitem);
if (maybe_item.has_value()) {
mission_items.push_back(maybe_item.value());
}
}
return {mission_items};
}
std::vector<MissionRaw::MissionItem>
MissionImport::import_polygon_geofences(const Json::Value& polygons)
{
std::vector<MissionRaw::MissionItem> polygon_geofences;
for (const auto& polygon : polygons) {
bool inclusion_missing = polygon["inclusion"].isNull();
bool inclusion = inclusion_missing ? true : polygon["inclusion"].asBool();
const auto& points = polygon["polygon"];
for (const auto& point : points) {
MissionRaw::MissionItem item{};
item.command = inclusion ? MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION :
MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION;
item.frame = MAV_FRAME_GLOBAL;
item.param1 = set_float(points.size());
item.x = set_int32(point[0]);
item.y = set_int32(point[1]);
item.mission_type = MAV_MISSION_TYPE_FENCE;
polygon_geofences.push_back(item);
}
}
return polygon_geofences;
}
std::vector<MissionRaw::MissionItem>
MissionImport::import_circular_geofences(const Json::Value& circles)
{
std::vector<MissionRaw::MissionItem> circular_geofences;
for (const auto& circle : circles) {
bool inclusion = circle["inclusion"].asBool();
const auto& center = circle["circle"]["center"];
const auto& radius = circle["circle"]["radius"];
MissionRaw::MissionItem item{};
item.command =
inclusion ? MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION : MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION;
item.frame = MAV_FRAME_GLOBAL;
item.param1 = set_float(radius);
item.x = set_int32(center[0]);
item.y = set_int32(center[1]);
item.mission_type = MAV_MISSION_TYPE_FENCE;
circular_geofences.push_back(item);
}
return circular_geofences;
}
float MissionImport::set_float(const Json::Value& val)
{
return val.isNull() ? NAN : val.asFloat();
}
int32_t MissionImport::set_int32(const Json::Value& val)
{
return static_cast<int32_t>(val.isNull() ? 0 : (std::round(val.asDouble() * 1e7)));
}
} // namespace mavsdk