Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
12241e62
Commit
12241e62
authored
Mar 16, 2018
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Restructure terrain query to support path query as well
parent
c7f4ac3d
Changes
5
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
480 additions
and
89 deletions
+480
-89
qgroundcontrol.pro
qgroundcontrol.pro
+3
-2
VisualMissionItem.cc
src/MissionManager/VisualMissionItem.cc
+4
-4
Terrain.h
src/Terrain.h
+0
-83
TerrainQuery.cc
src/Terrain/TerrainQuery.cc
+331
-0
TerrainQuery.h
src/Terrain/TerrainQuery.h
+142
-0
No files found.
qgroundcontrol.pro
View file @
12241e62
...
...
@@ -346,6 +346,7 @@ INCLUDEPATH += \
src
/
QtLocationPlugin
\
src
/
QtLocationPlugin
/
QMLControl
\
src
/
Settings
\
src
/
Terrain
\
src
/
VehicleSetup
\
src
/
ViewWidgets
\
src
/
Audio
\
...
...
@@ -586,7 +587,7 @@ HEADERS += \
src
/
Settings
/
SettingsManager
.
h
\
src
/
Settings
/
UnitsSettings
.
h
\
src
/
Settings
/
VideoSettings
.
h
\
src
/
Terrain
.
h
\
src
/
Terrain
/
TerrainQuery
.
h
\
src
/
Vehicle
/
MAVLinkLogManager
.
h
\
src
/
VehicleSetup
/
JoystickConfigController
.
h
\
src
/
comm
/
LinkConfiguration
.
h
\
...
...
@@ -778,7 +779,7 @@ SOURCES += \
src
/
Settings
/
SettingsManager
.
cc
\
src
/
Settings
/
UnitsSettings
.
cc
\
src
/
Settings
/
VideoSettings
.
cc
\
src
/
Terrain
.
cc
\
src
/
Terrain
/
TerrainQuery
.
cc
\
src
/
Vehicle
/
MAVLinkLogManager
.
cc
\
src
/
VehicleSetup
/
JoystickConfigController
.
cc
\
src
/
comm
/
LinkConfiguration
.
cc
\
...
...
src/MissionManager/VisualMissionItem.cc
View file @
12241e62
...
...
@@ -15,7 +15,7 @@
#include "FirmwarePluginManager.h"
#include "QGCApplication.h"
#include "JsonHelper.h"
#include "Terrain.h"
#include "Terrain
Query
.h"
const
char
*
VisualMissionItem
::
jsonTypeKey
=
"type"
;
const
char
*
VisualMissionItem
::
jsonTypeSimpleItemValue
=
"SimpleItem"
;
...
...
@@ -172,11 +172,11 @@ void VisualMissionItem::_reallyUpdateTerrainAltitude(void)
if
(
coord
.
isValid
()
&&
(
qIsNaN
(
_terrainAltitude
)
||
!
qFuzzyCompare
(
_lastLatTerrainQuery
,
coord
.
latitude
())
||
qFuzzyCompare
(
_lastLonTerrainQuery
,
coord
.
longitude
())))
{
_lastLatTerrainQuery
=
coord
.
latitude
();
_lastLonTerrainQuery
=
coord
.
longitude
();
ElevationProvider
*
terrain
=
new
ElevationProvider
(
this
);
connect
(
terrain
,
&
ElevationProvider
::
terrainData
,
this
,
&
VisualMissionItem
::
_terrainDataReceived
);
TerrainAtCoordinateQuery
*
terrain
=
new
TerrainAtCoordinateQuery
(
this
);
connect
(
terrain
,
&
TerrainAtCoordinateQuery
::
terrainData
,
this
,
&
VisualMissionItem
::
_terrainDataReceived
);
QList
<
QGeoCoordinate
>
rgCoord
;
rgCoord
.
append
(
coordinate
());
terrain
->
queryTerrain
Data
(
rgCoord
);
terrain
->
request
Data
(
rgCoord
);
}
}
...
...
src/Terrain.h
deleted
100644 → 0
View file @
c7f4ac3d
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "QGCLoggingCategory.h"
#include <QObject>
#include <QGeoCoordinate>
#include <QNetworkAccessManager>
#include <QTimer>
Q_DECLARE_LOGGING_CATEGORY
(
ElevationProviderLog
)
class
ElevationProvider
;
/// Used internally by ElevationProvider to batch requests together
class
TerrainBatchManager
:
public
QObject
{
Q_OBJECT
public:
TerrainBatchManager
(
void
);
void
addQuery
(
ElevationProvider
*
elevationProvider
,
const
QList
<
QGeoCoordinate
>&
coordinates
);
private
slots
:
void
_sendNextBatch
(
void
);
void
_requestFinished
(
void
);
void
_elevationProviderDestroyed
(
QObject
*
elevationProvider
);
private:
typedef
struct
{
ElevationProvider
*
elevationProvider
;
QList
<
QGeoCoordinate
>
coordinates
;
}
QueuedRequestInfo_t
;
typedef
struct
{
ElevationProvider
*
elevationProvider
;
bool
providerDestroyed
;
int
cCoord
;
}
SentRequestInfo_t
;
enum
class
State
{
Idle
,
Downloading
,
};
void
_batchFailed
(
void
);
QString
_stateToString
(
State
state
);
QList
<
QueuedRequestInfo_t
>
_requestQueue
;
QList
<
SentRequestInfo_t
>
_sentRequests
;
State
_state
=
State
::
Idle
;
QNetworkAccessManager
_networkManager
;
const
int
_batchTimeout
=
500
;
QTimer
_batchTimer
;
};
/// NOTE: ElevationProvider is not thread safe. All instances/calls to ElevationProvider must be on main thread.
class
ElevationProvider
:
public
QObject
{
Q_OBJECT
public:
ElevationProvider
(
QObject
*
parent
=
NULL
);
/// Async elevation query for a list of lon,lat coordinates. When the query is done, the terrainData() signal
/// is emitted.
/// @param coordinates to query
void
queryTerrainData
(
const
QList
<
QGeoCoordinate
>&
coordinates
);
// Internal method
void
_signalTerrainData
(
bool
success
,
QList
<
float
>&
altitudes
);
signals:
void
terrainData
(
bool
success
,
QList
<
float
>
altitudes
);
};
src/Terrain.cc
→
src/Terrain
/TerrainQuery
.cc
View file @
12241e62
This diff is collapsed.
Click to expand it.
src/Terrain/TerrainQuery.h
0 → 100644
View file @
12241e62
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "QGCLoggingCategory.h"
#include <QObject>
#include <QGeoCoordinate>
#include <QNetworkAccessManager>
#include <QNetworkReply>
#include <QTimer>
Q_DECLARE_LOGGING_CATEGORY
(
TerrainQueryLog
)
class
TerrainAtCoordinateQuery
;
// Base class for all terrain query objects
class
TerrainQuery
:
public
QObject
{
Q_OBJECT
public:
TerrainQuery
(
QObject
*
parent
=
NULL
);
protected:
// Send a query to AirMap terrain servers. Data and errors are returned back from super class virtual implementations.
// @param path Additional path to add to url
// @param urlQuery Query to send
void
_sendQuery
(
const
QString
&
path
,
const
QUrlQuery
&
urlQuery
);
virtual
void
_getNetworkReplyFailed
(
void
)
=
0
;
///< QNetworkManager::get failed to return QNetworkReplay object
virtual
void
_requestFailed
(
QNetworkReply
::
NetworkError
error
)
=
0
;
///< QNetworkReply::finished returned error
virtual
void
_requestJsonParseFailed
(
const
QString
&
errorString
)
=
0
;
///< Parsing of returned json failed
virtual
void
_requestAirmapStatusFailed
(
const
QString
&
status
)
=
0
;
///< AirMap status was not "success"
virtual
void
_requestSucess
(
const
QJsonValue
&
dataJsonValue
)
=
0
;
///< Successful reqest, data returned
private
slots
:
void
_requestFinished
(
void
);
private:
QNetworkAccessManager
_networkManager
;
};
/// Used internally by TerrainAtCoordinateQuery to batch coordinate requests together
class
TerrainAtCoordinateBatchManager
:
public
TerrainQuery
{
Q_OBJECT
public:
TerrainAtCoordinateBatchManager
(
void
);
void
addQuery
(
TerrainAtCoordinateQuery
*
terrainAtCoordinateQuery
,
const
QList
<
QGeoCoordinate
>&
coordinates
);
protected:
void
_getNetworkReplyFailed
(
void
)
final
;
void
_requestFailed
(
QNetworkReply
::
NetworkError
error
)
final
;
void
_requestJsonParseFailed
(
const
QString
&
errorString
)
final
;
void
_requestAirmapStatusFailed
(
const
QString
&
status
)
final
;
void
_requestSucess
(
const
QJsonValue
&
dataJsonValue
)
final
;
private
slots
:
void
_sendNextBatch
(
void
);
void
_queryObjectDestroyed
(
QObject
*
elevationProvider
);
private:
typedef
struct
{
TerrainAtCoordinateQuery
*
terrainAtCoordinateQuery
;
QList
<
QGeoCoordinate
>
coordinates
;
}
QueuedRequestInfo_t
;
typedef
struct
{
TerrainAtCoordinateQuery
*
terrainAtCoordinateQuery
;
bool
queryObjectDestroyed
;
int
cCoord
;
}
SentRequestInfo_t
;
enum
class
State
{
Idle
,
Downloading
,
};
void
_batchFailed
(
void
);
QString
_stateToString
(
State
state
);
QList
<
QueuedRequestInfo_t
>
_requestQueue
;
QList
<
SentRequestInfo_t
>
_sentRequests
;
State
_state
=
State
::
Idle
;
const
int
_batchTimeout
=
500
;
QTimer
_batchTimer
;
};
/// NOTE: TerrainAtCoordinateQuery is not thread safe. All instances/calls to ElevationProvider must be on main thread.
class
TerrainAtCoordinateQuery
:
public
QObject
{
Q_OBJECT
public:
TerrainAtCoordinateQuery
(
QObject
*
parent
=
NULL
);
/// Async terrain query for a list of lon,lat coordinates. When the query is done, the terrainData() signal
/// is emitted.
/// @param coordinates to query
void
requestData
(
const
QList
<
QGeoCoordinate
>&
coordinates
);
// Internal method
void
_signalTerrainData
(
bool
success
,
QList
<
float
>&
altitudes
);
signals:
void
terrainData
(
bool
success
,
QList
<
float
>
altitudes
);
};
class
TerrainPathQuery
:
public
TerrainQuery
{
Q_OBJECT
public:
TerrainPathQuery
(
QObject
*
parent
=
NULL
);
/// Async terrain query for terrain heights between two lat/lon coordinates. When the query is done, the terrainData() signal
/// is emitted.
/// @param coordinates to query
void
requestData
(
const
QGeoCoordinate
&
fromCoord
,
const
QGeoCoordinate
&
toCoord
);
protected:
void
_getNetworkReplyFailed
(
void
)
final
;
void
_requestFailed
(
QNetworkReply
::
NetworkError
error
)
final
;
void
_requestJsonParseFailed
(
const
QString
&
errorString
)
final
;
void
_requestAirmapStatusFailed
(
const
QString
&
status
)
final
;
void
_requestSucess
(
const
QJsonValue
&
dataJsonValue
)
final
;
signals:
/// Signalled when terrain data comes back from server
/// @param latStep Amount of latitudinal distance between each returned height
/// @param lonStep Amount of longitudinal distance between each returned height
/// @param altitudes Altitudes along specified path
void
terrainData
(
bool
success
,
double
latStep
,
double
lonStep
,
QList
<
double
>
altitudes
);
};
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment