Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
6cee3dfc
Commit
6cee3dfc
authored
Feb 15, 2018
by
Gus Grubba
Browse files
Compute bounding cube instead of "box"
parent
ba55604f
Changes
7
Hide whitespace changes
Inline
Side-by-side
src/MissionManager/ComplexMissionItem.h
View file @
6cee3dfc
...
...
@@ -11,6 +11,7 @@
#define ComplexMissionItem_H
#include
"VisualMissionItem.h"
#include
"QGCGeo.h"
class
ComplexMissionItem
:
public
VisualMissionItem
{
...
...
@@ -22,15 +23,14 @@ public:
const
ComplexMissionItem
&
operator
=
(
const
ComplexMissionItem
&
other
);
Q_PROPERTY
(
double
complexDistance
READ
complexDistance
NOTIFY
complexDistanceChanged
)
Q_PROPERTY
(
QRectF
boundingBox
READ
boundingBox
NOTIFY
boundingBoxChanged
)
/// @return The distance covered the complex mission item in meters.
/// Signals complexDistanceChanged
virtual
double
complexDistance
(
void
)
const
=
0
;
/// @return The item bounding
box (QRectf(West, Nort, East, South))
/// Signals bounding
Box
Changed
virtual
Q
RectF
bounding
Box
(
void
)
const
{
return
Q
RectF
();
}
/// @return The item bounding
cube
/// Signals bounding
Cube
Changed
virtual
Q
GCGeoBoundingCube
bounding
Cube
(
void
)
const
{
return
Q
GCGeoBoundingCube
();
}
/// @return Amount of additional time delay in seconds needed to fly the complex item
virtual
double
additionalTimeDelay
(
void
)
const
{
return
0
;
}
...
...
@@ -53,7 +53,7 @@ public:
signals:
void
complexDistanceChanged
(
void
);
void
bounding
Box
Changed
(
void
);
void
bounding
Cube
Changed
(
void
);
void
greatestDistanceToChanged
(
void
);
void
additionalTimeDelayChanged
(
void
);
};
...
...
src/MissionManager/MissionController.cc
View file @
6cee3dfc
...
...
@@ -440,7 +440,7 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
//-- Keep track of bounding box changes in complex items
if
(
!
newItem
->
isSimpleItem
())
{
connect
(
newItem
,
&
ComplexMissionItem
::
bounding
Box
Changed
,
this
,
&
MissionController
::
_complexBoundingBoxChanged
);
connect
(
newItem
,
&
ComplexMissionItem
::
bounding
Cube
Changed
,
this
,
&
MissionController
::
_complexBoundingBoxChanged
);
}
newItem
->
setSequenceNumber
(
sequenceNumber
);
_initVisualItem
(
newItem
);
...
...
@@ -1997,11 +1997,13 @@ void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
void
MissionController
::
_updateTimeout
()
{
Q
RectF
bounding
Box
;
Q
GCGeoBoundingCube
bounding
Cube
;
double
north
=
0.0
;
double
south
=
180.0
;
double
east
=
0.0
;
double
west
=
360.0
;
double
minAlt
=
QGCGeoBoundingCube
::
MaxAlt
;
double
maxAlt
=
QGCGeoBoundingCube
::
MinAlt
;
for
(
int
i
=
1
;
i
<
_visualItems
->
count
();
i
++
)
{
VisualMissionItem
*
item
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
i
));
if
(
item
->
isSimpleItem
())
{
...
...
@@ -2014,10 +2016,13 @@ void MissionController::_updateTimeout()
if
(
pSimpleItem
->
coordinate
().
isValid
())
{
double
lat
=
pSimpleItem
->
coordinate
().
latitude
()
+
90.0
;
double
lon
=
pSimpleItem
->
coordinate
().
longitude
()
+
180.0
;
double
alt
=
pSimpleItem
->
coordinate
().
altitude
();
north
=
fmax
(
north
,
lat
);
south
=
fmin
(
south
,
lat
);
east
=
fmax
(
east
,
lon
);
west
=
fmin
(
west
,
lon
);
minAlt
=
fmin
(
minAlt
,
alt
);
maxAlt
=
fmax
(
maxAlt
,
alt
);
}
break
;
default:
...
...
@@ -2027,20 +2032,24 @@ void MissionController::_updateTimeout()
}
else
{
ComplexMissionItem
*
pComplexItem
=
qobject_cast
<
ComplexMissionItem
*>
(
item
);
if
(
pComplexItem
)
{
QRectF
bb
=
pComplexItem
->
boundingBox
();
if
(
!
bb
.
isNull
())
{
north
=
fmax
(
north
,
bb
.
y
()
+
90.0
);
south
=
fmin
(
south
,
bb
.
height
()
+
90.0
);
east
=
fmax
(
east
,
bb
.
x
()
+
180.0
);
west
=
fmin
(
west
,
bb
.
width
()
+
180.0
);
QGCGeoBoundingCube
bc
=
pComplexItem
->
boundingCube
();
if
(
bc
.
isValid
())
{
north
=
fmax
(
north
,
bc
.
pointNW
.
latitude
()
+
90.0
);
south
=
fmin
(
south
,
bc
.
pointSE
.
latitude
()
+
90.0
);
east
=
fmax
(
east
,
bc
.
pointNW
.
longitude
()
+
180.0
);
west
=
fmin
(
west
,
bc
.
pointSE
.
longitude
()
+
180.0
);
minAlt
=
fmin
(
minAlt
,
bc
.
pointNW
.
altitude
());
maxAlt
=
fmax
(
maxAlt
,
bc
.
pointSE
.
altitude
());
}
}
}
}
boundingBox
=
QRectF
(
east
-
180.0
,
north
-
90.0
,
west
-
180.0
,
south
-
90.0
);
if
(
_boundingBox
!=
boundingBox
)
{
_boundingBox
=
boundingBox
;
qCDebug
(
MissionControllerLog
)
<<
"Bounding box:"
<<
_boundingBox
.
y
()
<<
_boundingBox
.
x
()
<<
_boundingBox
.
height
()
<<
_boundingBox
.
width
();
boundingCube
=
QGCGeoBoundingCube
(
QGeoCoordinate
(
north
-
90.0
,
west
-
180.0
,
minAlt
),
QGeoCoordinate
(
south
-
90.0
,
east
-
180.0
,
maxAlt
));
if
(
_travelBoundingCube
!=
boundingCube
)
{
_travelBoundingCube
=
boundingCube
;
qCDebug
(
MissionControllerLog
)
<<
"Bounding cube:"
<<
_travelBoundingCube
.
pointNW
<<
_travelBoundingCube
.
pointSE
;
}
}
...
...
src/MissionManager/MissionController.h
View file @
6cee3dfc
...
...
@@ -16,6 +16,7 @@
#include
"Vehicle.h"
#include
"QGCLoggingCategory.h"
#include
"MavlinkQmlSingleton.h"
#include
"QGCGeo.h"
#include
<QHash>
...
...
@@ -261,7 +262,7 @@ private:
int
_currentPlanViewIndex
;
VisualMissionItem
*
_currentPlanViewItem
;
QTimer
_updateTimer
;
Q
RectF
_b
ounding
Box
;
Q
GCGeoBoundingCube
_travelB
ounding
Cube
;
static
const
char
*
_settingsGroup
;
...
...
src/MissionManager/SurveyMissionItem.cc
View file @
6cee3dfc
...
...
@@ -163,11 +163,11 @@ void SurveyMissionItem::_setSurveyDistance(double surveyDistance)
}
}
void
SurveyMissionItem
::
_setBounding
Box
(
QRectF
b
b
)
void
SurveyMissionItem
::
_setBounding
Cube
(
QGCGeoBoundingCube
b
c
)
{
if
(
b
b
!=
_bounding
Box
)
{
_bounding
Box
=
b
b
;
emit
bounding
Box
Changed
();
if
(
b
c
!=
_bounding
Cube
)
{
_bounding
Cube
=
b
c
;
emit
bounding
Cube
Changed
();
}
}
...
...
@@ -668,6 +668,28 @@ int SurveyMissionItem::_calcMissionCommandCount(QList<QList<QGeoCoordinate>>& tr
return
missionCommandCount
;
}
void
SurveyMissionItem
::
_calcBoundingCube
()
{
// Calc bounding cube
double
north
=
0.0
;
double
south
=
180.0
;
double
east
=
0.0
;
double
west
=
360.0
;
for
(
int
i
=
0
;
i
<
_simpleGridPoints
.
count
();
i
++
)
{
QGeoCoordinate
coord
=
_simpleGridPoints
[
i
].
value
<
QGeoCoordinate
>
();
double
lat
=
coord
.
latitude
()
+
90.0
;
double
lon
=
coord
.
longitude
()
+
180.0
;
north
=
fmax
(
north
,
lat
);
south
=
fmin
(
south
,
lat
);
east
=
fmax
(
east
,
lon
);
west
=
fmin
(
west
,
lon
);
}
_setBoundingCube
(
QGCGeoBoundingCube
(
QGeoCoordinate
(
north
-
90.0
,
west
-
180.0
,
_gridAltitudeFact
.
rawValue
().
toDouble
()),
QGeoCoordinate
(
south
-
90.0
,
east
-
180.0
,
_gridAltitudeFact
.
rawValue
().
toDouble
())));
}
void
SurveyMissionItem
::
_generateGrid
(
void
)
{
if
(
_ignoreRecalc
)
{
...
...
@@ -733,28 +755,14 @@ void SurveyMissionItem::_generateGrid(void)
// Calc survey distance
double
surveyDistance
=
0.0
;
for
(
int
i
=
1
;
i
<
_simpleGridPoints
.
count
();
i
++
)
{
for
(
int
i
=
1
;
i
<
_simpleGridPoints
.
count
();
i
++
)
{
QGeoCoordinate
coord1
=
_simpleGridPoints
[
i
-
1
].
value
<
QGeoCoordinate
>
();
QGeoCoordinate
coord2
=
_simpleGridPoints
[
i
].
value
<
QGeoCoordinate
>
();
surveyDistance
+=
coord1
.
distanceTo
(
coord2
);
}
_setSurveyDistance
(
surveyDistance
);
// Calc bounding box
double
north
=
0.0
;
double
south
=
180.0
;
double
east
=
0.0
;
double
west
=
360.0
;
for
(
int
i
=
0
;
i
<
_simpleGridPoints
.
count
();
i
++
)
{
QGeoCoordinate
coord
=
_simpleGridPoints
[
i
].
value
<
QGeoCoordinate
>
();
double
lat
=
coord
.
latitude
()
+
90.0
;
double
lon
=
coord
.
longitude
()
+
180.0
;
north
=
fmax
(
north
,
lat
);
south
=
fmin
(
south
,
lat
);
east
=
fmax
(
east
,
lon
);
west
=
fmin
(
west
,
lon
);
}
_setBoundingBox
(
QRectF
(
east
-
180.0
,
north
-
90.0
,
west
-
180.0
,
south
-
90.0
));
// Calc bounding cube
_calcBoundingCube
();
if
(
cameraShots
==
0
&&
_triggerCamera
())
{
cameraShots
=
(
int
)
floor
(
surveyDistance
/
_triggerDistance
());
...
...
@@ -1315,6 +1323,7 @@ void SurveyMissionItem::applyNewAltitude(double newAltitude)
{
_fixedValueIsAltitudeFact
.
setRawValue
(
true
);
_gridAltitudeFact
.
setRawValue
(
newAltitude
);
_calcBoundingCube
();
}
void
SurveyMissionItem
::
setRefly90Degrees
(
bool
refly90Degrees
)
...
...
src/MissionManager/SurveyMissionItem.h
View file @
6cee3dfc
...
...
@@ -96,7 +96,7 @@ public:
// Overrides from ComplexMissionItem
double
complexDistance
(
void
)
const
final
{
return
_surveyDistance
;
}
Q
RectF
bounding
Box
(
void
)
const
final
{
return
_bounding
Box
;
}
Q
GCGeoBoundingCube
bounding
Cube
(
void
)
const
final
{
return
_bounding
Cube
;
}
double
additionalTimeDelay
(
void
)
const
final
{
return
_additionalFlightDelaySeconds
;
}
int
lastSequenceNumber
(
void
)
const
final
;
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
final
;
...
...
@@ -200,7 +200,7 @@ private:
void
_intersectLinesWithPolygon
(
const
QList
<
QLineF
>&
lineList
,
const
QPolygonF
&
polygon
,
QList
<
QLineF
>&
resultLines
);
void
_adjustLineDirection
(
const
QList
<
QLineF
>&
lineList
,
QList
<
QLineF
>&
resultLines
);
void
_setSurveyDistance
(
double
surveyDistance
);
void
_setBounding
Box
(
QRectF
b
b
);
void
_setBounding
Cube
(
QGCGeoBoundingCube
b
c
);
void
_setCameraShots
(
int
cameraShots
);
void
_setCoveredArea
(
double
coveredArea
);
void
_cameraValueChanged
(
void
);
...
...
@@ -226,6 +226,7 @@ private:
bool
_gridAngleIsNorthSouthTransects
();
double
_clampGridAngle90
(
double
gridAngle
);
int
_calcMissionCommandCount
(
QList
<
QList
<
QGeoCoordinate
>>&
transectSegments
);
void
_calcBoundingCube
();
int
_sequenceNumber
;
bool
_dirty
;
...
...
@@ -243,12 +244,12 @@ private:
bool
_ignoreRecalc
;
double
_surveyDistance
;
QRectF
_boundingBox
;
int
_cameraShots
;
double
_coveredArea
;
double
_timeBetweenShots
;
double
_cruiseSpeed
;
QGCGeoBoundingCube
_boundingCube
;
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
SettingsFact
_manualGridFact
;
...
...
src/QGCGeo.cc
View file @
6cee3dfc
...
...
@@ -102,3 +102,10 @@ void convertUTMToGeo(double easting, double northing, int zone, bool southhemi,
coord
.
setLatitude
(
RadToDeg
(
latRadians
));
coord
.
setLongitude
(
RadToDeg
(
lonRadians
));
}
double
QGCGeoBoundingCube
::
MaxAlt
=
1000000.0
;
double
QGCGeoBoundingCube
::
MinAlt
=
-
1000000.0
;
double
QGCGeoBoundingCube
::
MaxNorth
=
90.0
;
double
QGCGeoBoundingCube
::
MaxSouth
=
-
90.0
;
double
QGCGeoBoundingCube
::
MaxWest
=
-
180.0
;
double
QGCGeoBoundingCube
::
MaxEast
=
180.0
;
src/QGCGeo.h
View file @
6cee3dfc
...
...
@@ -81,4 +81,46 @@ int convertGeoToUTM(const QGeoCoordinate& coord, double& easting, double& northi
// The function does not return a value.
void
convertUTMToGeo
(
double
easting
,
double
northing
,
int
zone
,
bool
southhemi
,
QGeoCoordinate
&
coord
);
// A bounding cube
class
QGCGeoBoundingCube
{
public:
QGCGeoBoundingCube
()
:
pointNW
(
QGeoCoordinate
(
MaxSouth
,
MaxEast
,
MaxAlt
))
,
pointSE
(
QGeoCoordinate
(
MaxNorth
,
MaxWest
,
MinAlt
))
{
}
QGCGeoBoundingCube
(
QGeoCoordinate
p1
,
QGeoCoordinate
p2
)
:
pointNW
(
p1
)
,
pointSE
(
p2
)
{
}
QGeoCoordinate
pointNW
;
QGeoCoordinate
pointSE
;
inline
bool
operator
==
(
const
QGCGeoBoundingCube
&
other
)
{
return
pointNW
==
other
.
pointNW
&&
pointSE
==
other
.
pointSE
;
}
inline
bool
operator
!=
(
const
QGCGeoBoundingCube
&
other
)
{
return
!
(
*
this
==
other
);
}
inline
QGCGeoBoundingCube
operator
=
(
const
QGCGeoBoundingCube
&
other
)
{
pointNW
=
other
.
pointNW
;
pointSE
=
other
.
pointSE
;
return
*
this
;
}
inline
bool
isValid
()
{
return
pointNW
.
isValid
()
&&
pointSE
.
isValid
()
&&
pointNW
.
latitude
()
!=
MaxSouth
&&
pointSE
.
latitude
()
!=
MaxNorth
&&
\
pointNW
.
longitude
()
!=
MaxEast
&&
pointSE
.
longitude
()
!=
MaxWest
&&
pointNW
.
altitude
()
<
MaxAlt
and
pointSE
.
altitude
()
>
MinAlt
;
}
static
double
MaxAlt
;
static
double
MinAlt
;
static
double
MaxNorth
;
static
double
MaxSouth
;
static
double
MaxWest
;
static
double
MaxEast
;
};
#endif // QGCGEO_H
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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