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