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
ae02bcd2
Commit
ae02bcd2
authored
Nov 13, 2016
by
Don Gagne
Committed by
GitHub
Nov 13, 2016
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #4205 from DonLakeFlyer/MapViewport
Better Plan view map viewport handling
parents
0b83a2da
49177bc2
Changes
10
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
201 additions
and
105 deletions
+201
-105
APMGeoFenceManager.cc
src/FirmwarePlugin/APM/APMGeoFenceManager.cc
+22
-27
APMGeoFenceManager.h
src/FirmwarePlugin/APM/APMGeoFenceManager.h
+2
-1
APMRallyPointManager.cc
src/FirmwarePlugin/APM/APMRallyPointManager.cc
+1
-1
MissionEditor.qml
src/MissionEditor/MissionEditor.qml
+168
-72
GeoFenceController.cc
src/MissionManager/GeoFenceController.cc
+3
-2
GeoFenceController.h
src/MissionManager/GeoFenceController.h
+1
-0
GeoFenceManager.cc
src/MissionManager/GeoFenceManager.cc
+1
-1
RallyPointController.cc
src/MissionManager/RallyPointController.cc
+1
-0
RallyPointController.h
src/MissionManager/RallyPointController.h
+1
-0
RallyPointManager.cc
src/MissionManager/RallyPointManager.cc
+1
-1
No files found.
src/FirmwarePlugin/APM/APMGeoFenceManager.cc
View file @
ae02bcd2
...
...
@@ -22,11 +22,12 @@ APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle)
:
GeoFenceManager
(
vehicle
)
,
_fenceSupported
(
false
)
,
_breachReturnSupported
(
vehicle
->
fixedWing
())
,
_circleSupported
(
false
)
,
_polygonSupported
(
false
)
,
_firstParamLoadComplete
(
false
)
,
_circleRadiusFact
(
NULL
)
,
_readTransactionInProgress
(
false
)
,
_writeTransactionInProgress
(
false
)
,
_fenceEnableFact
(
NULL
)
,
_fenceTypeFact
(
NULL
)
{
connect
(
_vehicle
,
&
Vehicle
::
mavlinkMessageReceived
,
this
,
&
APMGeoFenceManager
::
_mavlinkMessageReceived
);
...
...
@@ -80,7 +81,7 @@ void APMGeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, const
fenceEnableFact
->
setRawValue
(
0
);
// Total point count, +1 polygon close in last index, +1 for breach in index 0
_cWriteFencePoints
=
(
validatedPolygonCount
?
(
validatedPolygonCount
+
1
)
:
0
)
+
1
;
_cWriteFencePoints
=
validatedPolygonCount
?
validatedPolygonCount
+
1
+
1
:
0
;
_vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
_fenceTotalParam
)
->
setRawValue
(
_cWriteFencePoints
);
// FIXME: No validation of correct fence received
...
...
@@ -106,11 +107,11 @@ void APMGeoFenceManager::loadFromVehicle(void)
return
;
}
// Point 0: Breach return point (ArduPlane only)
// Point 0: Breach return point (
always sent, but supported by
ArduPlane only)
// Point [1,N]: Polygon points
// Point N+1: Close polygon point (same as point 1)
int
cFencePoints
=
_vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
_fenceTotalParam
)
->
rawValue
().
toInt
();
int
minFencePoints
=
6
;
int
minFencePoints
=
5
;
qCDebug
(
GeoFenceManagerLog
)
<<
"APMGeoFenceManager::loadFromVehicle"
<<
cFencePoints
;
if
(
cFencePoints
==
0
)
{
// No fence
...
...
@@ -242,8 +243,19 @@ bool APMGeoFenceManager::_geoFenceSupported(void)
void
APMGeoFenceManager
::
_updateSupportedFlags
(
void
)
{
emit
circleSupportedChanged
(
circleSupported
());
emit
polygonSupportedChanged
(
polygonSupported
());
bool
newCircleSupported
=
_fenceSupported
&&
_vehicle
->
multiRotor
()
&&
_fenceTypeFact
&&
(
_fenceTypeFact
->
rawValue
().
toInt
()
&
2
);
if
(
newCircleSupported
!=
_circleSupported
)
{
_circleSupported
=
newCircleSupported
;
emit
circleSupportedChanged
(
newCircleSupported
);
}
bool
newPolygonSupported
=
_fenceSupported
&&
((
_vehicle
->
multiRotor
()
&&
_fenceTypeFact
&&
(
_fenceTypeFact
->
rawValue
().
toInt
()
&
4
))
||
_vehicle
->
fixedWing
());
if
(
newPolygonSupported
!=
_polygonSupported
)
{
_polygonSupported
=
newPolygonSupported
;
emit
polygonSupportedChanged
(
newPolygonSupported
);
}
}
void
APMGeoFenceManager
::
_parametersReady
(
void
)
...
...
@@ -258,11 +270,9 @@ void APMGeoFenceManager::_parametersReady(void)
QStringList
paramLabels
;
if
(
_vehicle
->
multiRotor
())
{
_fenceEnableFact
=
_vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"FENCE_ENABLE"
));
_fenceTypeFact
=
_vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"FENCE_TYPE"
));
connect
(
_fenceEnableFact
,
&
Fact
::
rawValueChanged
,
this
,
&
APMGeoFenceManager
::
_updateSupportedFlags
);
connect
(
_fenceTypeFact
,
&
Fact
::
rawValueChanged
,
this
,
&
APMGeoFenceManager
::
_updateSupportedFlags
);
connect
(
_fenceTypeFact
,
&
Fact
::
rawValueChanged
,
this
,
&
APMGeoFenceManager
::
_updateSupportedFlags
);
_circleRadiusFact
=
_vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"FENCE_RADIUS"
));
connect
(
_circleRadiusFact
,
&
Fact
::
rawValueChanged
,
this
,
&
APMGeoFenceManager
::
_circleRadiusRawValueChanged
);
...
...
@@ -293,8 +303,7 @@ void APMGeoFenceManager::_parametersReady(void)
emit
paramLabelsChanged
(
_paramLabels
);
emit
fenceSupportedChanged
(
_fenceSupported
);
emit
circleSupportedChanged
(
circleSupported
());
emit
polygonSupportedChanged
(
polygonSupported
());
_updateSupportedFlags
();
}
qCDebug
(
GeoFenceManagerLog
)
<<
"fenceSupported:circleSupported:polygonSupported:breachReturnSupported"
<<
...
...
@@ -318,26 +327,12 @@ void APMGeoFenceManager::_circleRadiusRawValueChanged(QVariant value)
bool
APMGeoFenceManager
::
circleSupported
(
void
)
const
{
if
(
_fenceSupported
&&
_vehicle
->
multiRotor
()
&&
_fenceEnableFact
&&
_fenceTypeFact
)
{
return
_fenceEnableFact
->
rawValue
().
toBool
()
&&
(
_fenceTypeFact
->
rawValue
().
toInt
()
&
2
);
}
return
false
;
return
_circleSupported
;
}
bool
APMGeoFenceManager
::
polygonSupported
(
void
)
const
{
if
(
_fenceSupported
)
{
if
(
_vehicle
->
multiRotor
())
{
if
(
_fenceEnableFact
&&
_fenceTypeFact
)
{
return
_fenceEnableFact
->
rawValue
().
toBool
()
&&
(
_fenceTypeFact
->
rawValue
().
toInt
()
&
4
);
}
}
else
if
(
_vehicle
->
fixedWing
())
{
return
true
;
}
}
return
false
;
return
_polygonSupported
;
}
QString
APMGeoFenceManager
::
editorQml
(
void
)
const
...
...
src/FirmwarePlugin/APM/APMGeoFenceManager.h
View file @
ae02bcd2
...
...
@@ -49,6 +49,8 @@ private:
private:
bool
_fenceSupported
;
bool
_breachReturnSupported
;
bool
_circleSupported
;
bool
_polygonSupported
;
bool
_firstParamLoadComplete
;
QVariantList
_params
;
...
...
@@ -63,7 +65,6 @@ private:
uint8_t
_cWriteFencePoints
;
uint8_t
_currentFencePoint
;
Fact
*
_fenceEnableFact
;
Fact
*
_fenceTypeFact
;
static
const
char
*
_fenceTotalParam
;
...
...
src/FirmwarePlugin/APM/APMRallyPointManager.cc
View file @
ae02bcd2
...
...
@@ -90,7 +90,7 @@ void APMRallyPointManager::_mavlinkMessageReceived(const mavlink_message_t& mess
QGeoCoordinate
point
((
float
)
rallyPoint
.
lat
/
1e7
,
(
float
)
rallyPoint
.
lng
/
1e7
,
rallyPoint
.
alt
);
_rgPoints
.
append
(
point
);
if
(
rallyPoint
.
idx
<
_cReadRallyPoints
-
2
)
{
if
(
rallyPoint
.
idx
<
_cReadRallyPoints
-
1
)
{
// Still more points to request
_requestRallyPoint
(
++
_currentRallyPoint
);
}
else
{
...
...
src/MissionEditor/MissionEditor.qml
View file @
ae02bcd2
This diff is collapsed.
Click to expand it.
src/MissionManager/GeoFenceController.cc
View file @
ae02bcd2
...
...
@@ -333,9 +333,9 @@ void GeoFenceController::loadFromVehicle(void)
void
GeoFenceController
::
sendToVehicle
(
void
)
{
if
(
_activeVehicle
->
parameterManager
()
->
parametersReady
()
&&
!
syncInProgress
())
{
setDirty
(
false
);
_polygon
.
setDirty
(
false
);
_activeVehicle
->
geoFenceManager
()
->
sendToVehicle
(
_breachReturnPoint
,
_polygon
.
coordinateList
());
_polygon
.
setDirty
(
false
);
setDirty
(
false
);
}
else
{
qCWarning
(
GeoFenceControllerLog
)
<<
"GeoFenceController::loadFromVehicle call at wrong time"
<<
_activeVehicle
->
parameterManager
()
->
parametersReady
()
<<
syncInProgress
();
}
...
...
@@ -433,6 +433,7 @@ void GeoFenceController::_loadComplete(const QGeoCoordinate& breachReturn, const
_setReturnPointFromManager
(
breachReturn
);
_setPolygonFromManager
(
polygon
);
setDirty
(
false
);
emit
loadComplete
();
}
QString
GeoFenceController
::
fileExtension
(
void
)
const
...
...
src/MissionManager/GeoFenceController.h
View file @
ae02bcd2
...
...
@@ -78,6 +78,7 @@ signals:
void
paramsChanged
(
QVariantList
params
);
void
paramLabelsChanged
(
QStringList
paramLabels
);
void
editorQmlChanged
(
QString
editorQml
);
void
loadComplete
(
void
);
private
slots
:
void
_polygonDirtyChanged
(
bool
dirty
);
...
...
src/MissionManager/GeoFenceManager.cc
View file @
ae02bcd2
...
...
@@ -34,7 +34,7 @@ void GeoFenceManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
void
GeoFenceManager
::
loadFromVehicle
(
void
)
{
// No geofence support in unknown vehicle
loadComplete
(
QGeoCoordinate
(),
QList
<
QGeoCoordinate
>
());
emit
loadComplete
(
QGeoCoordinate
(),
QList
<
QGeoCoordinate
>
());
}
void
GeoFenceManager
::
sendToVehicle
(
const
QGeoCoordinate
&
breachReturn
,
const
QList
<
QGeoCoordinate
>&
polygon
)
...
...
src/MissionManager/RallyPointController.cc
View file @
ae02bcd2
...
...
@@ -254,6 +254,7 @@ void RallyPointController::_loadComplete(const QList<QGeoCoordinate> rgPoints)
_points
.
swapObjectList
(
pointList
);
setDirty
(
false
);
_setFirstPointCurrent
();
emit
loadComplete
();
}
QString
RallyPointController
::
fileExtension
(
void
)
const
...
...
src/MissionManager/RallyPointController.h
View file @
ae02bcd2
...
...
@@ -61,6 +61,7 @@ public:
signals:
void
rallyPointsSupportedChanged
(
bool
rallyPointsSupported
);
void
currentRallyPointChanged
(
QObject
*
rallyPoint
);
void
loadComplete
(
void
);
private
slots
:
void
_loadComplete
(
const
QList
<
QGeoCoordinate
>
rgPoints
);
...
...
src/MissionManager/RallyPointManager.cc
View file @
ae02bcd2
...
...
@@ -34,7 +34,7 @@ void RallyPointManager::_sendError(ErrorCode_t errorCode, const QString& errorMs
void
RallyPointManager
::
loadFromVehicle
(
void
)
{
// No support in generic vehicle
loadComplete
(
QList
<
QGeoCoordinate
>
());
emit
loadComplete
(
QList
<
QGeoCoordinate
>
());
}
void
RallyPointManager
::
sendToVehicle
(
const
QList
<
QGeoCoordinate
>&
rgPoints
)
...
...
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