Newer
Older
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
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
#include "CircularSurvey.h"
#include <QtConcurrentRun>
#include "JsonHelper.h"
#include "QGCApplication.h"
#include <chrono>
#include "clipper/clipper.hpp"
#include "snake.h"
#define CLIPPER_SCALE 10000
template <int k> ClipperLib::cInt get(ClipperLib::IntPoint &p);
#include "Geometry/GenericCircle.h"
#include "Geometry/GeoUtilities.h"
#include "Geometry/PlanimetryCalculus.h"
#include "Geometry/PolygonCalculus.h"
#include <boost/units/io.hpp>
#include <boost/units/systems/si.hpp>
template <> ClipperLib::cInt get<0>(ClipperLib::IntPoint &p) { return p.X; }
template <> ClipperLib::cInt get<1>(ClipperLib::IntPoint &p) { return p.Y; }
template <class Functor> class CommandRAII {
public:
CommandRAII(Functor f) : fun(f) {}
~CommandRAII() { fun(); }
private:
Functor fun;
};
const char *CircularSurvey::settingsGroup = "CircularSurvey";
const char *CircularSurvey::deltaRName = "DeltaR";
const char *CircularSurvey::deltaAlphaName = "DeltaAlpha";
const char *CircularSurvey::transectMinLengthName = "TransectMinLength";
const char *CircularSurvey::reverseName = "Reverse";
const char *CircularSurvey::maxWaypointsName = "MaxWaypoints";
const char *CircularSurvey::CircularSurveyName = "CircularSurvey";
const char *CircularSurvey::refPointLatitudeName = "ReferencePointLat";
const char *CircularSurvey::refPointLongitudeName = "ReferencePointLong";
const char *CircularSurvey::refPointAltitudeName = "ReferencePointAlt";
CircularSurvey::CircularSurvey(Vehicle *vehicle, bool flyView,
const QString &kmlOrShpFile, QObject *parent)
: TransectStyleComplexItem(vehicle, flyView, settingsGroup, parent),
_referencePoint(QGeoCoordinate(0, 0, 0)),
_metaDataMap(FactMetaData::createMapFromJsonFile(
QStringLiteral(":/json/CircularSurvey.SettingsGroup.json"), this)),
_deltaR(settingsGroup, _metaDataMap[deltaRName]),
_deltaAlpha(settingsGroup, _metaDataMap[deltaAlphaName]),
_minLength(settingsGroup, _metaDataMap[transectMinLengthName]),
_reverse(settingsGroup, _metaDataMap[reverseName]),
_maxWaypoints(settingsGroup, _metaDataMap[maxWaypointsName]),
_isInitialized(false), _calculating(false), _cancle(false) {
Q_UNUSED(kmlOrShpFile)
_editorQml = "qrc:/qml/CircularSurveyItemEditor.qml";
// Defer update if facts or ref. changes.
connect(&_deltaR, &Fact::valueChanged, this, &CircularSurvey::_deferUpdate);
connect(&_deltaAlpha, &Fact::valueChanged, this,
&CircularSurvey::_deferUpdate);
connect(&_minLength, &Fact::valueChanged, this,
&CircularSurvey::_deferUpdate);
connect(&_maxWaypoints, &Fact::valueChanged, [this] {
this->CircularSurvey::_deferUpdate();
qWarning() << "max waypoints implementaion missing";
});
connect(&_reverse, &Fact::valueChanged, [this] {
this->CircularSurvey::_deferUpdate();
qWarning() << "reverse implementaion missing";
});
connect(this, &CircularSurvey::refPointChanged, this,
&CircularSurvey::_deferUpdate);
connect(&this->_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this,
&CircularSurvey::_deferUpdate);
// Setup Timer.
_timer.setSingleShot(true);
connect(&_timer, &QTimer::timeout, [this] { this->_rebuildTransects(); });
// Future watcher.
connect(&_watcher, &Watcher::finished, [this] {
this->_calculating = false;
emit calculatingChanged();
if (!_cancle) {
this->_transectsDirty = false;
} else {
_cancle = false;
}
this->_rebuildTransects();
});
}
void CircularSurvey::resetReference() {
setRefPoint(_surveyAreaPolygon.center());
}
void CircularSurvey::setRefPoint(const QGeoCoordinate &refPt) {
if (refPt != _referencePoint) {
_referencePoint = refPt;
emit refPointChanged();
}
}
void CircularSurvey::setIsInitialized(bool isInitialized) {
if (isInitialized != _isInitialized) {
_isInitialized = isInitialized;
emit isInitializedChanged();
}
}
QGeoCoordinate CircularSurvey::refPoint() const { return _referencePoint; }
Fact *CircularSurvey::deltaR() { return &_deltaR; }
Fact *CircularSurvey::deltaAlpha() { return &_deltaAlpha; }
bool CircularSurvey::isInitialized() { return _isInitialized; }
bool CircularSurvey::load(const QJsonObject &complexObject, int sequenceNumber,
QString &errorString) {
// We need to pull version first to determine what validation/conversion needs
// to be performed
QList<JsonHelper::KeyValidateInfo> versionKeyInfoList = {
{JsonHelper::jsonVersionKey, QJsonValue::Double, true},
};
if (!JsonHelper::validateKeys(complexObject, versionKeyInfoList,
errorString)) {
return false;
}
int version = complexObject[JsonHelper::jsonVersionKey].toInt();
if (version != 1) {
errorString = tr("Survey items do not support version %1").arg(version);
return false;
}
QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{VisualMissionItem::jsonTypeKey, QJsonValue::String, true},
{ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true},
{deltaRName, QJsonValue::Double, true},
{deltaAlphaName, QJsonValue::Double, true},
{transectMinLengthName, QJsonValue::Double, true},
{reverseName, QJsonValue::Bool, true},
{refPointLatitudeName, QJsonValue::Double, true},
{refPointLongitudeName, QJsonValue::Double, true},
{refPointAltitudeName, QJsonValue::Double, true},
};
if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
return false;
}
QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
QString complexType =
complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
if (itemType != VisualMissionItem::jsonTypeComplexItemValue ||
complexType != CircularSurveyName) {
errorString =
tr("%1 does not support loading this complex mission item type: %2:%3")
.arg(qgcApp()->applicationName())
.arg(itemType)
.arg(complexType);
return false;
}
_ignoreRecalc = true;
setSequenceNumber(sequenceNumber);
if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */,
errorString)) {
_surveyAreaPolygon.clear();
return false;
}
if (!_load(complexObject, errorString)) {
_ignoreRecalc = false;
return false;
}
_deltaR.setRawValue(complexObject[deltaRName].toDouble());
_deltaAlpha.setRawValue(complexObject[deltaAlphaName].toDouble());
_minLength.setRawValue(complexObject[transectMinLengthName].toDouble());
_referencePoint.setLongitude(complexObject[refPointLongitudeName].toDouble());
_referencePoint.setLatitude(complexObject[refPointLatitudeName].toDouble());
_referencePoint.setAltitude(complexObject[refPointAltitudeName].toDouble());
_reverse.setRawValue(complexObject[reverseName].toBool());
setIsInitialized(true);
_ignoreRecalc = false;
_recalcComplexDistance();
if (_cameraShots == 0) {
// Shot count was possibly not available from plan file
_recalcCameraShots();
}
return true;
}
QString CircularSurvey::mapVisualQML() const {
return QStringLiteral("CircularSurveyMapVisual.qml");
}
void CircularSurvey::save(QJsonArray &planItems) {
QJsonObject saveObject;
_save(saveObject);
saveObject[JsonHelper::jsonVersionKey] = 1;
saveObject[VisualMissionItem::jsonTypeKey] =
VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = CircularSurveyName;
saveObject[deltaRName] = _deltaR.rawValue().toDouble();
saveObject[deltaAlphaName] = _deltaAlpha.rawValue().toDouble();
saveObject[transectMinLengthName] = _minLength.rawValue().toDouble();
saveObject[reverseName] = _reverse.rawValue().toBool();
saveObject[refPointLongitudeName] = _referencePoint.longitude();
saveObject[refPointLatitudeName] = _referencePoint.latitude();
saveObject[refPointAltitudeName] = _referencePoint.altitude();
// Polygon shape
_surveyAreaPolygon.saveToJson(saveObject);
planItems.append(saveObject);
}
bool CircularSurvey::specifiesCoordinate() const { return true; }
void CircularSurvey::appendMissionItems(QList<MissionItem *> &items,
QObject *missionItemParent) {
if (_transectsDirty)
return;
if (_loadedMissionItems.count()) {
// We have mission items from the loaded plan, use those
_appendLoadedMissionItems(items, missionItemParent);
} else {
// Build the mission items on the fly
_buildAndAppendMissionItems(items, missionItemParent);
}
}
void CircularSurvey::_appendLoadedMissionItems(QList<MissionItem *> &items,
QObject *missionItemParent) {
if (_transectsDirty)
return;
int seqNum = _sequenceNumber;
for (const MissionItem *loadedMissionItem : _loadedMissionItems) {
MissionItem *item = new MissionItem(*loadedMissionItem, missionItemParent);
item->setSequenceNumber(seqNum++);
items.append(item);
}
}
void CircularSurvey::_buildAndAppendMissionItems(QList<MissionItem *> &items,
QObject *missionItemParent) {
if (_transectsDirty)
return;
MissionItem *item;
int seqNum = _sequenceNumber;
MAV_FRAME mavFrame =
followTerrain() || !_cameraCalc.distanceToSurfaceRelative()
? MAV_FRAME_GLOBAL
: MAV_FRAME_GLOBAL_RELATIVE_ALT;
for (const QList<TransectStyleComplexItem::CoordInfo_t> &transect :
_transects) {
// bool transectEntry = true;
for (const CoordInfo_t &transectCoordInfo : transect) {
item = new MissionItem(
seqNum++, MAV_CMD_NAV_WAYPOINT, mavFrame,
0, // Hold time (delay for hover and capture to settle vehicle before
// image is taken)
0.0, // No acceptance radius specified
0.0, // Pass through waypoint
std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
transectCoordInfo.coord.latitude(),
transectCoordInfo.coord.longitude(),
transectCoordInfo.coord.altitude(),
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
}
}
void CircularSurvey::applyNewAltitude(double newAltitude) {
_cameraCalc.valueSetIsDistance()->setRawValue(true);
_cameraCalc.distanceToSurface()->setRawValue(newAltitude);
_cameraCalc.setDistanceToSurfaceRelative(true);
}
double CircularSurvey::timeBetweenShots() { return 1; }
QString CircularSurvey::commandDescription() const {
return tr("Circular Survey");
}
QString CircularSurvey::commandName() const { return tr("Circular Survey"); }
QString CircularSurvey::abbreviation() const { return tr("C.S."); }
bool CircularSurvey::readyForSave() const {
return TransectStyleComplexItem::readyForSave() && !_transectsDirty;
}
double CircularSurvey::additionalTimeDelay() const { return 0; }
void CircularSurvey::_rebuildTransectsPhase1(void) {
if (_calculating)
return;
if (!_transectsDirty) {
auto pTransects = _watcher.result();
if (pTransects) {
#ifdef DEBUG_CIRCULAR_SURVEY
qWarning()
<< "CircularSurvey::_rebuildTransectsPhase1(): storing transects.";
#endif
// If the transects are getting rebuilt then any previously loaded
// mission items are now invalid.
if (_loadedMissionItemsParent) {
_loadedMissionItems.clear();
_loadedMissionItemsParent->deleteLater();
_loadedMissionItemsParent = nullptr;
}
// Store new transects;
_transects = *pTransects;
}
} else {
_transects.clear();
// Check preconitions
#ifdef DEBUG_CIRCULAR_SURVEY
qWarning()
<< "CircularSurvey::_rebuildTransectsPhase1(): checking preconditions.";
#endif
if (_isInitialized && _surveyAreaPolygon.count() >= 3 &&
_deltaAlpha.rawValue() <= _deltaAlpha.rawMax() &&
_deltaAlpha.rawValue() >= _deltaAlpha.rawMin() &&
_deltaR.rawValue() <= _deltaR.rawMax() &&
_deltaR.rawValue() >= _deltaR.rawMin()) {
#ifdef DEBUG_CIRCULAR_SURVEY
qWarning()
<< "CircularSurvey::_rebuildTransectsPhase1(): preconditions ok.";
#endif
using namespace boost::units;
_calculating = true;
emit calculatingChanged();
// Copy input.
const auto &polygon = this->_surveyAreaPolygon.coordinateList();
const auto &origin = this->_referencePoint;
const snake::Length deltaR(this->_deltaR.rawValue().toDouble() *
si::meter);
const snake::Angle deltaAlpha(this->_deltaAlpha.rawValue().toDouble() *
degree::degree);
const snake::Length minLength(this->_minLength.rawValue().toDouble() *
si::meter);
const auto maxWaypoints(this->_maxWaypoints.rawValue().toUInt());
auto future = QtConcurrent::run([polygon, origin, deltaAlpha, minLength,
maxWaypoints, deltaR] {
#ifdef DEBUG_CIRCULAR_SURVEY
qWarning() << "CircularSurvey::_rebuildTransectsPhase1(): calculation "
"started.";
#endif
#ifdef SHOW_CIRCULAR_SURVEY_TIME
auto start = std::chrono::high_resolution_clock::now();
auto onExit = [&start] {
qWarning() << "CircularSurvey: concurrent update execution time: "
<< std::chrono::duration_cast<std::chrono::milliseconds>(
std::chrono::high_resolution_clock::now() - start)
.count()
<< " ms";
};
CommandRAII<decltype(onExit)> commandRAII(onExit);
#endif
// Convert geo polygon to ENU polygon.
snake::BoostPolygon polygonENU;
snake::BoostPoint originENU{0, 0};
snake::areaToEnu(origin, polygon, polygonENU);
// Check validity.
if (!bg::is_valid(polygonENU)) {
#ifdef DEBUG_CIRCULAR_SURVEY
qWarning() << "CircularSurvey::_rebuildTransectsPhase1(): "
"invalid polygon.";
#endif
return PtrTransects();
} else {
// Calculate polygon distances and angles.
std::vector<snake::Length> distances;
distances.reserve(polygonENU.outer().size());
std::vector<snake::Angle> angles;
angles.reserve(polygonENU.outer().size());
for (const auto &p : polygonENU.outer()) {
distances.push_back(bg::distance(originENU, p) * si::meter);
angles.push_back((std::atan2(p.get<1>(), p.get<0>()) + M_PI) *
si::radian);
}
auto rMin = deltaR; // minimal circle radius
snake::Angle alpha1(0 * degree::degree);
snake::Angle alpha2(360 * degree::degree);
bool refInside = true;
// Determine r_min by successive approximation
if (!bg::within(originENU, polygonENU)) {
rMin = bg::distance(originENU, polygonENU) * si::meter;
alpha1 = (*std::min_element(angles.begin(), angles.end()));
alpha2 = (*std::max_element(angles.begin(), angles.end()));
refInside = false;
}
auto rMax =
(*std::max_element(distances.begin(),
distances.end())); // maximal circle radius
// Scale parameters and coordinates.
const auto rMinScaled =
ClipperLib::cInt(std::round(rMin.value() * CLIPPER_SCALE));
const auto deltaRScaled =
ClipperLib::cInt(std::round(deltaR.value() * CLIPPER_SCALE));
auto originScaled = ClipperLib::IntPoint{
ClipperLib::cInt(std::round(originENU.get<0>())),
ClipperLib::cInt(std::round(originENU.get<1>()))};
// Generate circle sectors.
auto rScaled = rMinScaled;
const auto nTran = long(std::floor(((rMax - rMin) / deltaR).value()));
vector<ClipperLib::Path> sectors(nTran, ClipperLib::Path());
const auto nSectors =
long(std::round(((alpha2 - alpha1) / deltaAlpha).value()));
#ifdef DEBUG_CIRCULAR_SURVEY
qWarning() << "sector parameres:";
qWarning() << "alpha1: " << to_string(alpha1).c_str();
qWarning() << "alpha2: " << to_string(alpha2).c_str();
qWarning() << "n: "
<< to_string((alpha2 - alpha1) / deltaAlpha).c_str();
qWarning() << "nSectors: " << nSectors;
qWarning() << "rMin: " << to_string(rMin).c_str();
qWarning() << "rMax: " << to_string(rMax).c_str();
qWarning() << "nTran: " << nTran;
qWarning() << "refInside: " << refInside;
#endif
using ClipperCircle =
GenericCircle<ClipperLib::cInt, ClipperLib::IntPoint>;
// Helper lambda.
std::function<void(ClipperCircle & circle,
ClipperLib::Path & sectors)>
approx;
if (refInside) {
approx = [nSectors](ClipperCircle &circle,
ClipperLib::Path §or) {
approximate(circle, nSectors, sector);
};
} else {
approx = [nSectors, alpha1, alpha2](ClipperCircle &circle,
ClipperLib::Path §or) {
approximate(circle, nSectors, alpha1, alpha2, sector);
};
}
for (auto §or : sectors) {
ClipperCircle circle(rScaled, originScaled);
approx(circle, sector);
rScaled += deltaRScaled;
}
// Clip sectors to polygonENU.
ClipperLib::Path polygonClipper;
auto &outer = polygonENU.outer();
polygonClipper.reserve(outer.size() - 1);
for (auto it = outer.begin(); it < outer.end() - 1; ++it) {
auto x = ClipperLib::cInt(std::round(it->get<0>() * CLIPPER_SCALE));
auto y = ClipperLib::cInt(std::round(it->get<1>() * CLIPPER_SCALE));
polygonClipper.push_back(ClipperLib::IntPoint{x, y});
}
ClipperLib::Clipper clipper;
clipper.AddPath(polygonClipper, ClipperLib::ptClip, true);
clipper.AddPaths(sectors, ClipperLib::ptSubject, false);
ClipperLib::PolyTree transectsClipper;
clipper.Execute(ClipperLib::ctIntersection, transectsClipper,
ClipperLib::pftNonZero, ClipperLib::pftNonZero);
// Extract transects from PolyTree and convert them to
// BoostLineString
snake::Transects transectsENU;
for (const auto &child : transectsClipper.Childs) {
snake::BoostLineString transect;
transect.reserve(child->Contour.size());
for (const auto &vertex : child->Contour) {
auto x = static_cast<double>(vertex.X) / CLIPPER_SCALE;
auto y = static_cast<double>(vertex.Y) / CLIPPER_SCALE;
transect.push_back(snake::BoostPoint(x, y));
}
if (bg::length(transect) >= minLength.value()) {
transectsENU.push_back(transect);
}
}
if (transectsENU.size() == 0) {
#ifdef DEBUG_CIRCULAR_SURVEY
qWarning() << "CircularSurvey::_rebuildTransectsPhase1(): "
"not able to generate transects.";
#endif
return PtrTransects();
}
// Route transects;
snake::Transects transectsRouted;
snake::Route route;
std::string errorString;
bool success = snake::route(polygonENU, transectsENU, transectsRouted,
route, errorString);
if (!success) {
#ifdef DEBUG_CIRCULAR_SURVEY
qWarning() << "CircularSurvey::_rebuildTransectsPhase1(): "
"routing failed.";
#endif
return PtrTransects();
}
QList<CoordInfo_t> transectList;
transectList.reserve(route.size());
for (const auto &vertex : route) {
QGeoCoordinate c;
snake::fromENU(origin, vertex, c);
CoordInfo_t coordinfo = {c, CoordTypeInterior};
transectList.append(coordinfo);
}
PtrTransects transects(new Transects());
transects->append(transectList);
#ifdef DEBUG_CIRCULAR_SURVEY
qWarning() << "CircularSurvey::_rebuildTransectsPhase1(): "
"concurrent update success.";
#endif
return transects;
}
}); // QtConcurrent::run()
_watcher.setFuture(future);
}
#ifdef DEBUG_CIRCULAR_SURVEY
else {
qWarning()
<< "CircularSurvey::_rebuildTransectsPhase1(): preconditions failed.";
}
#endif
}
}
void CircularSurvey::_recalcComplexDistance() {
_complexDistance = 0;
if (_transectsDirty)
return;
for (int i = 0; i < _visualTransectPoints.count() - 1; i++) {
_complexDistance +=
_visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(
_visualTransectPoints[i + 1].value<QGeoCoordinate>());
}
emit complexDistanceChanged();
}
// no cameraShots in Circular Survey, add if desired
void CircularSurvey::_recalcCameraShots() { _cameraShots = 0; }
void CircularSurvey::_deferUpdate() {
if (!_calculating) {
#ifdef DEBUG_CIRCULAR_SURVEY
qWarning() << "CircularSurvey::_deferUpdate(): defer update.";
#endif
_transectsDirty = true;
if (_timer.isActive()) {
_timer.stop();
}
_timer.start(100 /*ms*/);
} else {
_cancle = true;
}
}
Fact *CircularSurvey::transectMinLength() { return &_minLength; }
Fact *CircularSurvey::reverse() { return &_reverse; }
Fact *CircularSurvey::maxWaypoints() { return &_maxWaypoints; }
bool CircularSurvey::calculating() { return _calculating; }
/*!
\class CircularSurveyComplexItem
\inmodule Wima
\brief The \c CircularSurveyComplexItem class provides a survey mission item
with circular transects around a point of interest.
CircularSurveyComplexItem class provides a survey mission item with circular
transects around a point of interest. Within the \c Wima module it's used to
scan a defined area with constant angle (circular transects) to the base
station (point of interest).
\sa WimaArea
*/