QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
SHPFileHelper.cc
Go to the documentation of this file.
1#include "SHPFileHelper.h"
2#include "QGCGeo.h"
4
5#include <QtCore/QFile>
6#include <QtCore/QRegularExpression>
7#include <QtCore/QScopeGuard>
8#include <QtCore/QTextStream>
9
10#include "shapefil.h"
11
12QGC_LOGGING_CATEGORY(SHPFileHelperLog, "Utilities.SHPFileHelper")
13
14namespace {
15 constexpr const char *_errorPrefix = QT_TR_NOOP("SHP file load failed. %1");
16
17 // QFile-based hooks for shapelib to support Qt Resource System (qrc:/) paths.
18 // This allows loading shapefiles embedded in the application binary.
19
20 SAFile qfileOpen(const char *filename, const char *access, void *pvUserData)
21 {
22 Q_UNUSED(pvUserData);
23
24 if (!filename || !access) {
25 qCWarning(SHPFileHelperLog) << "QFile open called with null filename or access mode";
26 return nullptr;
27 }
28
29 // Only support read mode - shapefiles are read-only in QGC
30 if (access[0] != 'r') {
31 qCWarning(SHPFileHelperLog) << "QFile hooks only support read mode, requested:" << access;
32 return nullptr;
33 }
34
35 auto *file = new QFile(QString::fromUtf8(filename));
36 if (!file->open(QIODevice::ReadOnly)) {
37 qCWarning(SHPFileHelperLog) << "Failed to open file:" << filename << file->errorString();
38 delete file;
39 return nullptr;
40 }
41
42 return reinterpret_cast<SAFile>(file);
43 }
44
45 SAOffset qfileRead(void *p, SAOffset size, SAOffset nmemb, SAFile file)
46 {
47 if (!file || !p || size == 0) {
48 return 0;
49 }
50 auto *qfile = reinterpret_cast<QFile *>(file);
51 const qint64 bytesRequested = static_cast<qint64>(size) * static_cast<qint64>(nmemb);
52 const qint64 bytesRead = qfile->read(static_cast<char *>(p), bytesRequested);
53 if (bytesRead < 0) {
54 return 0;
55 }
56 return static_cast<SAOffset>(bytesRead / static_cast<qint64>(size));
57 }
58
59 SAOffset qfileWrite(const void *p, SAOffset size, SAOffset nmemb, SAFile file)
60 {
61 Q_UNUSED(p);
62 Q_UNUSED(size);
63 Q_UNUSED(nmemb);
64 Q_UNUSED(file);
65 qCWarning(SHPFileHelperLog) << "QFile write not supported - shapefiles are read-only in QGC";
66 return 0;
67 }
68
69 SAOffset qfileSeek(SAFile file, SAOffset offset, int whence)
70 {
71 if (!file) {
72 return -1;
73 }
74 auto *qfile = reinterpret_cast<QFile *>(file);
75 qint64 newPos = 0;
76
77 switch (whence) {
78 case SEEK_SET:
79 newPos = static_cast<qint64>(offset);
80 break;
81 case SEEK_CUR:
82 newPos = qfile->pos() + static_cast<qint64>(offset);
83 break;
84 case SEEK_END:
85 newPos = qfile->size() + static_cast<qint64>(offset);
86 break;
87 default:
88 return -1;
89 }
90
91 if (newPos < 0) {
92 return -1;
93 }
94
95 return qfile->seek(newPos) ? 0 : -1;
96 }
97
98 SAOffset qfileTell(SAFile file)
99 {
100 if (!file) {
101 return 0;
102 }
103 auto *qfile = reinterpret_cast<QFile *>(file);
104 return static_cast<SAOffset>(qfile->pos());
105 }
106
107 int qfileFlush(SAFile file)
108 {
109 Q_UNUSED(file);
110 // No-op for read-only files
111 return 0;
112 }
113
114 int qfileClose(SAFile file)
115 {
116 if (!file) {
117 return 0;
118 }
119 auto *qfile = reinterpret_cast<QFile *>(file);
120 qfile->close();
121 delete qfile;
122 return 0;
123 }
124
125 void setupQFileHooks(SAHooks *hooks)
126 {
127 SASetupDefaultHooks(hooks);
128 hooks->FOpen = qfileOpen;
129 hooks->FRead = qfileRead;
130 hooks->FWrite = qfileWrite;
131 hooks->FSeek = qfileSeek;
132 hooks->FTell = qfileTell;
133 hooks->FFlush = qfileFlush;
134 hooks->FClose = qfileClose;
135 hooks->Error = [](const char *message) {
136 qCWarning(SHPFileHelperLog) << "SHP Error:" << message;
137 };
138 }
139}
140
142{
147 bool _validateSHPFiles(const QString &shpFile, int *utmZone, bool *utmSouthernHemisphere, QString &errorString);
148
151 SHPHandle _loadShape(const QString &shpFile, int *utmZone, bool *utmSouthernHemisphere, QString &errorString);
152}
153
154bool SHPFileHelper::_validateSHPFiles(const QString &shpFile, int *utmZone, bool *utmSouthernHemisphere, QString &errorString)
155{
156 *utmZone = 0;
157 errorString.clear();
158
159 if (!shpFile.endsWith(QStringLiteral(".shp"), Qt::CaseInsensitive)) {
160 errorString = QString(_errorPrefix).arg(QString(QT_TRANSLATE_NOOP("SHP", "File is not a .shp file: %1")).arg(shpFile));
161 return false;
162 }
163
164 const QString prjFilename = shpFile.left(shpFile.length() - 4) + QStringLiteral(".prj");
165 QFile prjFile(prjFilename);
166 if (!prjFile.exists()) {
167 errorString = QString(_errorPrefix).arg(QString(QT_TRANSLATE_NOOP("SHP", "File not found: %1")).arg(prjFilename));
168 return false;
169 }
170
171 if (!prjFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
172 errorString = QString(_errorPrefix).arg(QObject::tr("PRJ file open failed: %1").arg(prjFile.errorString()));
173 return false;
174 }
175
176 QTextStream strm(&prjFile);
177 const QString line = strm.readLine();
178 if (line.startsWith(QStringLiteral("GEOGCS[\"GCS_WGS_1984\","))) {
179 *utmZone = 0;
180 *utmSouthernHemisphere = false;
181 } else if (line.startsWith(QStringLiteral("PROJCS[\"WGS_1984_UTM_Zone_"))) {
182 static const QRegularExpression regEx(QStringLiteral("^PROJCS\\[\"WGS_1984_UTM_Zone_(\\d{1,2})([NS])"));
183 const QRegularExpressionMatch regExMatch = regEx.match(line);
184 const QStringList rgCapture = regExMatch.capturedTexts();
185 if (rgCapture.count() == 3) {
186 const int zone = rgCapture[1].toInt();
187 if ((zone >= 1) && (zone <= 60)) {
188 *utmZone = zone;
189 *utmSouthernHemisphere = (rgCapture[2] == QStringLiteral("S"));
190 }
191 }
192
193 if (*utmZone == 0) {
194 errorString = QString(_errorPrefix).arg(QT_TRANSLATE_NOOP("SHP", "UTM projection is not in supported format. Must be PROJCS[\"WGS_1984_UTM_Zone_##N/S"));
195 }
196 } else {
197 // Extract projection name from WKT for error reporting
198 // Format is either GEOGCS["name",... or PROJCS["name",...
199 QString projectionName;
200 static const QRegularExpression nameRegEx(QStringLiteral("^(?:GEOGCS|PROJCS)\\[\"([^\"]+)\""));
201 const QRegularExpressionMatch nameMatch = nameRegEx.match(line);
202 if (nameMatch.hasMatch()) {
203 projectionName = nameMatch.captured(1);
204 }
205
206 if (!projectionName.isEmpty()) {
207 errorString = QString(_errorPrefix).arg(
208 QString(QT_TRANSLATE_NOOP("SHP", "Unsupported projection: %1. Supported projections are: WGS84 (GEOGCS[\"GCS_WGS_1984\"]) and UTM (PROJCS[\"WGS_1984_UTM_Zone_##N/S\"]). Convert your shapefile to WGS84 using QGIS or ogr2ogr."))
209 .arg(projectionName));
210 } else {
211 errorString = QString(_errorPrefix).arg(
212 QT_TRANSLATE_NOOP("SHP", "Unable to parse projection from PRJ file. Supported projections are: WGS84 (GEOGCS[\"GCS_WGS_1984\"]) and UTM (PROJCS[\"WGS_1984_UTM_Zone_##N/S\"])."));
213 }
214 }
215
216 return errorString.isEmpty();
217}
218
219SHPHandle SHPFileHelper::_loadShape(const QString &shpFile, int *utmZone, bool *utmSouthernHemisphere, QString &errorString)
220{
221 errorString.clear();
222
223 if (!_validateSHPFiles(shpFile, utmZone, utmSouthernHemisphere, errorString)) {
224 return nullptr;
225 }
226
227 // Use QFile-based hooks for Qt Resource System compatibility (qrc:/ paths)
228 SAHooks sHooks{};
229 setupQFileHooks(&sHooks);
230
231 SHPHandle shpHandle = SHPOpenLL(shpFile.toUtf8().constData(), "rb", &sHooks);
232 if (!shpHandle) {
233 errorString = QString(_errorPrefix).arg(QT_TRANSLATE_NOOP("SHP", "SHPOpen failed."));
234 }
235
236 return shpHandle;
237}
238
239ShapeFileHelper::ShapeType SHPFileHelper::determineShapeType(const QString &shpFile, QString &errorString)
240{
241 using ShapeType = ShapeFileHelper::ShapeType;
242
243 ShapeType shapeType = ShapeType::Error;
244
245 errorString.clear();
246
247 int utmZone;
248 bool utmSouthernHemisphere;
249 SHPHandle shpHandle = SHPFileHelper::_loadShape(shpFile, &utmZone, &utmSouthernHemisphere, errorString);
250 if (errorString.isEmpty()) {
251 Q_CHECK_PTR(shpHandle);
252
253 int cEntities, type;
254 SHPGetInfo(shpHandle, &cEntities, &type, nullptr, nullptr);
255 qCDebug(SHPFileHelperLog) << "SHPGetInfo" << shpHandle << cEntities << type;
256 if (cEntities < 1) {
257 errorString = QString(_errorPrefix).arg(QT_TRANSLATE_NOOP("SHP", "No entities found."));
258 } else if (type == SHPT_POLYGON || type == SHPT_POLYGONZ) {
259 shapeType = ShapeType::Polygon;
260 } else if (type == SHPT_ARC || type == SHPT_ARCZ) {
261 shapeType = ShapeType::Polyline;
262 } else if (type == SHPT_POINT || type == SHPT_POINTZ) {
263 shapeType = ShapeType::Point;
264 } else {
265 errorString = QString(_errorPrefix).arg(QT_TRANSLATE_NOOP("SHP", "No supported types found."));
266 }
267 }
268
269 if (shpHandle) {
270 SHPClose(shpHandle);
271 }
272
273 return shapeType;
274}
275
276int SHPFileHelper::getEntityCount(const QString &shpFile, QString &errorString)
277{
278 errorString.clear();
279
280 int utmZone;
281 bool utmSouthernHemisphere;
282 SHPHandle shpHandle = SHPFileHelper::_loadShape(shpFile, &utmZone, &utmSouthernHemisphere, errorString);
283 if (!shpHandle) {
284 return 0;
285 }
286
287 int cEntities, type;
288 SHPGetInfo(shpHandle, &cEntities, &type, nullptr, nullptr);
289 SHPClose(shpHandle);
290
291 return cEntities;
292}
293
294bool SHPFileHelper::loadPolygonsFromFile(const QString &shpFile, QList<QList<QGeoCoordinate>> &polygons, QString &errorString, double filterMeters)
295{
296 int utmZone = 0;
297 bool utmSouthernHemisphere = false;
298 SHPHandle shpHandle = nullptr;
299
300 errorString.clear();
301 polygons.clear();
302
303 auto cleanup = qScopeGuard([&]() {
304 if (shpHandle) SHPClose(shpHandle);
305 });
306
307 shpHandle = SHPFileHelper::_loadShape(shpFile, &utmZone, &utmSouthernHemisphere, errorString);
308 if (!errorString.isEmpty()) {
309 return false;
310 }
311 Q_CHECK_PTR(shpHandle);
312
313 int cEntities, shapeType;
314 SHPGetInfo(shpHandle, &cEntities, &shapeType, nullptr, nullptr);
315 if (shapeType != SHPT_POLYGON && shapeType != SHPT_POLYGONZ) {
316 errorString = QString(_errorPrefix).arg(QObject::tr("File contains %1, expected Polygon.").arg(SHPTypeName(shapeType)));
317 return false;
318 }
319
320 const bool hasAltitude = (shapeType == SHPT_POLYGONZ);
321
322 for (int entityIdx = 0; entityIdx < cEntities; entityIdx++) {
323 SHPObject *shpObject = SHPReadObject(shpHandle, entityIdx);
324 if (!shpObject) {
325 qCWarning(SHPFileHelperLog) << "Failed to read polygon entity" << entityIdx;
326 continue;
327 }
328 auto shpObjectCleanup = qScopeGuard([shpObject]() { SHPDestroyObject(shpObject); });
329
330 // Ensure clockwise winding for outer rings (QGC requirement)
331 SHPRewindObject(shpHandle, shpObject);
332
333 // For multi-part polygons (e.g., polygons with holes), we extract only the outer ring.
334 // In shapefiles, the first part is conventionally the outer boundary, and subsequent
335 // parts are holes (inner rings). For QGC's use cases (survey areas, geofences), the
336 // outer boundary is what matters for mission planning.
337 const int firstPartEnd = (shpObject->nParts > 1) ? shpObject->panPartStart[1] : shpObject->nVertices;
338 if (shpObject->nParts > 1) {
339 qCDebug(SHPFileHelperLog) << "Polygon entity" << entityIdx << "has" << shpObject->nParts
340 << "parts; using outer ring only (" << firstPartEnd << "vertices)";
341 }
342
343 QList<QGeoCoordinate> vertices;
344 const bool entityHasAltitude = hasAltitude && shpObject->padfZ;
345
346 for (int i = 0; i < firstPartEnd; i++) {
347 QGeoCoordinate coord;
348 if (utmZone) {
349 if (!QGCGeo::convertUTMToGeo(shpObject->padfX[i], shpObject->padfY[i], utmZone, utmSouthernHemisphere, coord)) {
350 qCWarning(SHPFileHelperLog) << "UTM conversion failed for entity" << entityIdx << "vertex" << i;
351 continue;
352 }
353 } else {
354 coord.setLatitude(shpObject->padfY[i]);
355 coord.setLongitude(shpObject->padfX[i]);
356 }
357 if (entityHasAltitude) {
358 coord.setAltitude(shpObject->padfZ[i]);
359 }
360 vertices.append(coord);
361 }
362
363 if (vertices.count() < 3) {
364 qCWarning(SHPFileHelperLog) << "Skipping polygon entity" << entityIdx << "with less than 3 vertices";
365 continue;
366 }
367
368 // Filter nearby vertices if enabled
369 if (filterMeters > 0) {
370 const QGeoCoordinate firstVertex = vertices.first();
371
372 // Detect explicit closure vertex (shapefile rings often repeat first vertex as last).
373 // Use a very small threshold (0.01m) so we only treat truly identical points as closure.
374 constexpr double kClosureThreshold = 0.01;
375 const bool hadExplicitClosure = vertices.last().distanceTo(firstVertex) < kClosureThreshold;
376
377 // Filter consecutive vertices that are too close together
378 int i = 0;
379 while (i < (vertices.count() - 1)) {
380 if ((vertices.count() > 3) && (vertices[i].distanceTo(vertices[i + 1]) < filterMeters)) {
381 vertices.removeAt(i + 1);
382 } else {
383 i++;
384 }
385 }
386
387 // If the original polygon had an explicit closure vertex, remove a single trailing
388 // duplicate after filtering, but do not strip distinct vertices that merely happen
389 // to be within filterMeters of the first.
390 if (hadExplicitClosure && vertices.count() > 3 &&
391 vertices.last().distanceTo(firstVertex) < kClosureThreshold) {
392 vertices.removeLast();
393 }
394 }
395
396 polygons.append(vertices);
397 }
398
399 if (polygons.isEmpty()) {
400 errorString = QString(_errorPrefix).arg(QT_TRANSLATE_NOOP("SHP", "No valid polygons found."));
401 return false;
402 }
403
404 return true;
405}
406
407bool SHPFileHelper::loadPolylinesFromFile(const QString &shpFile, QList<QList<QGeoCoordinate>> &polylines, QString &errorString, double filterMeters)
408{
409 int utmZone = 0;
410 bool utmSouthernHemisphere = false;
411 SHPHandle shpHandle = nullptr;
412
413 errorString.clear();
414 polylines.clear();
415
416 auto cleanup = qScopeGuard([&]() {
417 if (shpHandle) SHPClose(shpHandle);
418 });
419
420 shpHandle = SHPFileHelper::_loadShape(shpFile, &utmZone, &utmSouthernHemisphere, errorString);
421 if (!errorString.isEmpty()) {
422 return false;
423 }
424 Q_CHECK_PTR(shpHandle);
425
426 int cEntities, shapeType;
427 SHPGetInfo(shpHandle, &cEntities, &shapeType, nullptr, nullptr);
428 if (shapeType != SHPT_ARC && shapeType != SHPT_ARCZ) {
429 errorString = QString(_errorPrefix).arg(QObject::tr("File contains %1, expected Arc.").arg(SHPTypeName(shapeType)));
430 return false;
431 }
432
433 const bool hasAltitude = (shapeType == SHPT_ARCZ);
434
435 for (int entityIdx = 0; entityIdx < cEntities; entityIdx++) {
436 SHPObject *shpObject = SHPReadObject(shpHandle, entityIdx);
437 if (!shpObject) {
438 qCWarning(SHPFileHelperLog) << "Failed to read polyline entity" << entityIdx;
439 continue;
440 }
441 auto shpObjectCleanup = qScopeGuard([shpObject]() { SHPDestroyObject(shpObject); });
442
443 // For multi-part polylines (disconnected segments), we extract only the first part.
444 // This maintains consistency with polygon handling and provides the primary path.
445 // Each part in a multi-part polyline is typically a separate disconnected segment.
446 const int firstPartEnd = (shpObject->nParts > 1) ? shpObject->panPartStart[1] : shpObject->nVertices;
447 if (shpObject->nParts > 1) {
448 qCDebug(SHPFileHelperLog) << "Polyline entity" << entityIdx << "has" << shpObject->nParts
449 << "parts; using first part only (" << firstPartEnd << "vertices)";
450 }
451
452 QList<QGeoCoordinate> vertices;
453 const bool entityHasAltitude = hasAltitude && shpObject->padfZ;
454
455 for (int i = 0; i < firstPartEnd; i++) {
456 QGeoCoordinate coord;
457 if (utmZone) {
458 if (!QGCGeo::convertUTMToGeo(shpObject->padfX[i], shpObject->padfY[i], utmZone, utmSouthernHemisphere, coord)) {
459 qCWarning(SHPFileHelperLog) << "UTM conversion failed for entity" << entityIdx << "vertex" << i;
460 continue;
461 }
462 } else {
463 coord.setLatitude(shpObject->padfY[i]);
464 coord.setLongitude(shpObject->padfX[i]);
465 }
466 if (entityHasAltitude) {
467 coord.setAltitude(shpObject->padfZ[i]);
468 }
469 vertices.append(coord);
470 }
471
472 if (vertices.count() < 2) {
473 qCWarning(SHPFileHelperLog) << "Skipping polyline entity" << entityIdx << "with less than 2 vertices";
474 continue;
475 }
476
477 // Filter nearby vertices if enabled
478 if (filterMeters > 0) {
479 int i = 0;
480 while (i < (vertices.count() - 1)) {
481 if ((vertices.count() > 2) && (vertices[i].distanceTo(vertices[i+1]) < filterMeters)) {
482 vertices.removeAt(i+1);
483 } else {
484 i++;
485 }
486 }
487 }
488
489 polylines.append(vertices);
490 }
491
492 if (polylines.isEmpty()) {
493 errorString = QString(_errorPrefix).arg(QT_TRANSLATE_NOOP("SHP", "No valid polylines found."));
494 return false;
495 }
496
497 return true;
498}
499
500bool SHPFileHelper::loadPointsFromFile(const QString &shpFile, QList<QGeoCoordinate> &points, QString &errorString)
501{
502 int utmZone = 0;
503 bool utmSouthernHemisphere = false;
504 SHPHandle shpHandle = nullptr;
505
506 errorString.clear();
507 points.clear();
508
509 auto cleanup = qScopeGuard([&]() {
510 if (shpHandle) SHPClose(shpHandle);
511 });
512
513 shpHandle = SHPFileHelper::_loadShape(shpFile, &utmZone, &utmSouthernHemisphere, errorString);
514 if (!errorString.isEmpty()) {
515 return false;
516 }
517 Q_CHECK_PTR(shpHandle);
518
519 int cEntities, shapeType;
520 SHPGetInfo(shpHandle, &cEntities, &shapeType, nullptr, nullptr);
521 if (shapeType != SHPT_POINT && shapeType != SHPT_POINTZ) {
522 errorString = QString(_errorPrefix).arg(QObject::tr("File contains %1, expected Point.").arg(SHPTypeName(shapeType)));
523 return false;
524 }
525
526 const bool hasAltitude = (shapeType == SHPT_POINTZ);
527
528 for (int entityIdx = 0; entityIdx < cEntities; entityIdx++) {
529 SHPObject *shpObject = SHPReadObject(shpHandle, entityIdx);
530 if (!shpObject) {
531 qCWarning(SHPFileHelperLog) << "Failed to read point entity" << entityIdx;
532 continue;
533 }
534 auto shpObjectCleanup = qScopeGuard([shpObject]() { SHPDestroyObject(shpObject); });
535
536 // Point shapes have exactly one vertex per entity
537 if (shpObject->nVertices != 1) {
538 qCWarning(SHPFileHelperLog) << "Skipping point entity" << entityIdx << "with unexpected vertex count:" << shpObject->nVertices;
539 continue;
540 }
541
542 QGeoCoordinate coord;
543 if (utmZone) {
544 if (!QGCGeo::convertUTMToGeo(shpObject->padfX[0], shpObject->padfY[0], utmZone, utmSouthernHemisphere, coord)) {
545 qCWarning(SHPFileHelperLog) << "UTM conversion failed for point entity" << entityIdx;
546 continue;
547 }
548 } else {
549 coord.setLatitude(shpObject->padfY[0]);
550 coord.setLongitude(shpObject->padfX[0]);
551 }
552
553 if (hasAltitude && shpObject->padfZ) {
554 coord.setAltitude(shpObject->padfZ[0]);
555 }
556
557 points.append(coord);
558 }
559
560 if (points.isEmpty()) {
561 errorString = QString(_errorPrefix).arg(QT_TRANSLATE_NOOP("SHP", "No valid points found."));
562 return false;
563 }
564
565 return true;
566}
QString errorString
Geographic coordinate conversion utilities using GeographicLib.
#define QGC_LOGGING_CATEGORY(name, categoryStr)
constexpr const char * _errorPrefix
bool convertUTMToGeo(double easting, double northing, int zone, bool southhemi, QGeoCoordinate &coord)
Definition QGCGeo.cc:161
ShapeFileHelper::ShapeType determineShapeType(const QString &file, QString &errorString)
bool loadPointsFromFile(const QString &shpFile, QList< QGeoCoordinate > &points, QString &errorString)
Load all point entities.
int getEntityCount(const QString &shpFile, QString &errorString)
Get the number of entities in the shapefile.
bool loadPolygonsFromFile(const QString &shpFile, QList< QList< QGeoCoordinate > > &polygons, QString &errorString, double filterMeters=ShapeFileHelper::kDefaultVertexFilterMeters)
SHPHandle _loadShape(const QString &shpFile, int *utmZone, bool *utmSouthernHemisphere, QString &errorString)
bool _validateSHPFiles(const QString &shpFile, int *utmZone, bool *utmSouthernHemisphere, QString &errorString)
bool loadPolylinesFromFile(const QString &shpFile, QList< QList< QGeoCoordinate > > &polylines, QString &errorString, double filterMeters=ShapeFileHelper::kDefaultVertexFilterMeters)