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
243a826b
Commit
243a826b
authored
Oct 26, 2019
by
Valentin Platzgummer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
auto update in wima planer, after load imporved
parent
071506a9
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
91 additions
and
74 deletions
+91
-74
WimaController.cc
src/Wima/WimaController.cc
+0
-19
WimaDataContainer.h
src/Wima/WimaDataContainer.h
+1
-3
WimaPlaner.cc
src/Wima/WimaPlaner.cc
+66
-31
WimaPlaner.h
src/Wima/WimaPlaner.h
+21
-18
WimaToolBar.qml
src/WimaView/WimaToolBar.qml
+3
-3
No files found.
src/Wima/WimaController.cc
View file @
243a826b
...
...
@@ -204,20 +204,6 @@ bool WimaController::uploadToVehicle()
// _missionController->removeAll();
// return;
// }
for
(
int
i
=
1
;
i
<
visuals
->
count
();
i
++
)
{
SimpleMissionItem
*
item
=
visuals
->
value
<
SimpleMissionItem
*>
(
i
);
qWarning
()
<<
item
->
coordinate
();
qWarning
()
<<
item
->
command
();
qWarning
()
<<
item
->
missionItem
().
param1
();
qWarning
()
<<
item
->
missionItem
().
param2
();
qWarning
()
<<
item
->
missionItem
().
param3
();
qWarning
()
<<
item
->
missionItem
().
param4
();
qWarning
()
<<
item
->
missionItem
().
param5
();
qWarning
()
<<
item
->
missionItem
().
param6
();
qWarning
()
<<
item
->
missionItem
().
param7
();
qWarning
(
" "
);
}
_masterController
->
sendToVehicle
();
return
true
;
...
...
@@ -560,11 +546,6 @@ bool WimaController::calcNextPhase()
}
SimpleMissionItem
*
visualItemCopy
=
new
SimpleMissionItem
(
*
visualItem
,
true
,
this
);
qWarning
()
<<
visualItem
->
command
();
qWarning
()
<<
visualItem
->
coordinate
();
qWarning
()
<<
visualItemCopy
->
command
();
qWarning
()
<<
visualItemCopy
->
command
();
qWarning
(
" "
);
_currentMissionItems
.
append
(
visualItemCopy
);
}
...
...
src/Wima/WimaDataContainer.h
View file @
243a826b
...
...
@@ -12,9 +12,7 @@ public:
WimaDataContainer
(
WimaDataContainer
&
other
,
QObject
*
parent
=
nullptr
)
=
delete
;
WimaDataContainer
(
WimaDataContainer
&
other
)
=
delete
;
Q_INVOKABLE
WimaDataContainer
*
pointerToThis
()
{
return
this
;}
bool
dataValid
()
const
;
Q_INVOKABLE
WimaDataContainer
*
pointerToThis
()
{
return
this
;}
signals:
void
newDataAvailable
(
void
);
...
...
src/Wima/WimaPlaner.cc
View file @
243a826b
...
...
@@ -9,20 +9,20 @@ const char* WimaPlaner::areaItemsName = "AreaItems";
const
char
*
WimaPlaner
::
missionItemsName
=
"MissionItems"
;
WimaPlaner
::
WimaPlaner
(
QObject
*
parent
)
:
QObject
(
parent
)
,
_
dirty
(
false
)
,
_c
urrentAreaIndex
(
-
1
)
,
_
container
(
nullptr
)
,
_
joinedArea
(
this
)
,
_
measurementArea
(
this
)
,
_
serviceArea
(
this
)
,
_c
orridor
(
this
)
,
_
circularSurvey
(
nullptr
)
,
_s
urveyRefChanging
(
false
)
:
QObject
(
parent
)
,
_
currentAreaIndex
(
-
1
)
,
_c
ontainer
(
nullptr
)
,
_
joinedArea
(
this
)
,
_
measurementArea
(
this
)
,
_
serviceArea
(
this
)
,
_
corridor
(
this
)
,
_c
ircularSurvey
(
nullptr
)
,
_
surveyRefChanging
(
false
)
,
_s
yncronizedWithController
(
false
)
{
connect
(
this
,
&
WimaPlaner
::
currentPolygonIndexChanged
,
this
,
&
WimaPlaner
::
recalcPolygonInteractivity
);
connect
(
&
_updateTimer
,
&
QTimer
::
timeout
,
this
,
&
WimaPlaner
::
updateTimerSlot
);
_updateTimer
.
setInterval
(
25
0
);
// 250 ms means: max update time 2*250 ms
_updateTimer
.
setInterval
(
50
0
);
// 250 ms means: max update time 2*250 ms
_updateTimer
.
start
();
}
...
...
@@ -77,17 +77,16 @@ void WimaPlaner::setCurrentPolygonIndex(int index)
void
WimaPlaner
::
setDataContainer
(
WimaDataContainer
*
container
)
{
if
(
container
!=
nullptr
)
{
if
(
_container
!=
nullptr
)
{
disconnect
(
this
,
&
WimaPlaner
::
dirtyChanged
,
_container
,
&
WimaDataContainer
::
newDataAvailable
);
}
_container
=
container
;
connect
(
this
,
&
WimaPlaner
::
dirtyChanged
,
_container
,
&
WimaDataContainer
::
newDataAvailable
);
emit
dataContainerChanged
();
}
}
bool
WimaPlaner
::
syncronizedWithController
()
{
return
_syncronizedWithController
;
}
void
WimaPlaner
::
removeArea
(
int
index
)
{
if
(
index
>=
0
&&
index
<
_visualItems
.
count
()){
...
...
@@ -178,6 +177,10 @@ void WimaPlaner::removeAll()
_currentFile
=
""
;
_circularSurvey
=
nullptr
;
_surveyRefChanging
=
false
;
emit
currentFileChanged
();
if
(
changesApplied
)
emit
visualItemsChanged
();
...
...
@@ -213,8 +216,11 @@ bool WimaPlaner::updateMission()
return
false
;
}
// establish connections
_circularSurvey
->
setRefPoint
(
_measurementArea
.
center
());
_lastSurveyRefPoint
=
_measurementArea
.
center
();
_surveyRefChanging
=
false
;
_circularSurvey
->
setAutoGenerated
(
true
);
// prevents reinitialisation from gui
connect
(
_circularSurvey
->
deltaR
(),
&
Fact
::
rawValueChanged
,
this
,
&
WimaPlaner
::
calcArrivalAndReturnPath
);
connect
(
_circularSurvey
->
deltaAlpha
(),
&
Fact
::
rawValueChanged
,
this
,
&
WimaPlaner
::
calcArrivalAndReturnPath
);
...
...
@@ -228,8 +234,6 @@ bool WimaPlaner::updateMission()
calcArrivalAndReturnPath
();
pushToContainer
();
// exchange plan data with the WimaController via the _container
setDirty
(
false
);
return
true
;
}
...
...
@@ -414,6 +418,32 @@ bool WimaPlaner::loadFromFile(const QString &filename)
// load from temporary file
_masterController
->
loadFromFile
(
temporaryFileName
);
QmlObjectListModel
*
missionItems
=
_missionController
->
visualItems
();
_circularSurvey
=
nullptr
;
for
(
int
i
=
0
;
i
<
missionItems
->
count
();
i
++
)
{
_circularSurvey
=
missionItems
->
value
<
CircularSurveyComplexItem
*>
(
i
);
if
(
_circularSurvey
!=
nullptr
)
{
if
(
!
recalcJoinedArea
(
errorString
))
{
qgcApp
()
->
showMessage
(
tr
(
errorString
.
toLocal8Bit
().
data
()));
return
false
;
}
_lastSurveyRefPoint
=
_circularSurvey
->
refPoint
();
_surveyRefChanging
=
false
;
_circularSurvey
->
setAutoGenerated
(
true
);
// prevents reinitialisation from gui
connect
(
_circularSurvey
->
deltaR
(),
&
Fact
::
rawValueChanged
,
this
,
&
WimaPlaner
::
calcArrivalAndReturnPath
);
connect
(
_circularSurvey
->
deltaAlpha
(),
&
Fact
::
rawValueChanged
,
this
,
&
WimaPlaner
::
calcArrivalAndReturnPath
);
connect
(
_circularSurvey
->
isSnakePath
(),
&
Fact
::
rawValueChanged
,
this
,
&
WimaPlaner
::
calcArrivalAndReturnPath
);
connect
(
_circularSurvey
->
transectMinLength
(),
&
Fact
::
rawValueChanged
,
this
,
&
WimaPlaner
::
calcArrivalAndReturnPath
);
break
;
}
}
if
(
_circularSurvey
==
nullptr
)
updateMission
();
// remove temporary file
if
(
!
temporaryFile
.
remove
()
){
qWarning
(
"WimaPlaner::loadFromFile(): not able to remove temporary file."
);
...
...
@@ -454,6 +484,10 @@ bool WimaPlaner::calcArrivalAndReturnPath()
return
false
;
}
bool
restorePlanViewIndex
=
false
;
if
(
surveyIndex
==
_missionController
->
currentPlanViewIndex
())
restorePlanViewIndex
=
true
;
// remove old arrival and return path
int
size
=
missionItems
->
count
();
for
(
int
i
=
surveyIndex
+
1
;
i
<
size
;
i
++
)
...
...
@@ -548,7 +582,9 @@ bool WimaPlaner::calcArrivalAndReturnPath()
return
false
;
}
if
(
restorePlanViewIndex
)
_missionController
->
setCurrentPlanViewIndex
(
missionItems
->
indexOf
(
_circularSurvey
),
false
);
setSyncronizedWithControllerFalse
();
return
true
;
}
...
...
@@ -593,6 +629,7 @@ void WimaPlaner::pushToContainer()
if
(
_container
!=
nullptr
)
{
WimaPlanData
planData
=
toPlanData
();
_container
->
push
(
planData
);
setSyncronizedWithController
(
true
);
}
else
{
qWarning
(
"WimaPlaner::uploadToContainer(): no container assigned."
);
}
...
...
@@ -665,21 +702,14 @@ WimaPlanData WimaPlaner::toPlanData()
return
planData
;
}
void
WimaPlaner
::
set
Dirty
(
bool
dirty
)
void
WimaPlaner
::
set
SyncronizedWithController
(
bool
sync
)
{
if
(
_dirty
!=
dirty
)
{
_dirty
=
dirty
;
emit
dirtyChanged
(
_dirty
);
if
(
_syncronizedWithController
!=
sync
)
{
_syncronizedWithController
=
sync
;
emit
syncronizedWithControllerChanged
();
}
}
void
WimaPlaner
::
setDirtyTrue
()
{
setDirty
(
true
);
}
void
WimaPlaner
::
updateTimerSlot
()
{
// General operation of this function:
...
...
@@ -704,6 +734,11 @@ void WimaPlaner::updateTimerSlot()
_lastSurveyRefPoint
=
_circularSurvey
->
refPoint
()
;
}
void
WimaPlaner
::
setSyncronizedWithControllerFalse
()
{
setSyncronizedWithController
(
false
);
}
QJsonDocument
WimaPlaner
::
saveToJson
(
FileType
fileType
)
{
/// This function save all areas (of WimaPlaner) and all mission items (of MissionController) to a QJsonDocument
...
...
src/Wima/WimaPlaner.h
View file @
243a826b
...
...
@@ -59,8 +59,7 @@ public:
Q_PROPERTY
(
QString
fileExtension
READ
fileExtension
CONSTANT
)
Q_PROPERTY
(
QGeoCoordinate
joinedAreaCenter
READ
joinedAreaCenter
CONSTANT
)
Q_PROPERTY
(
WimaDataContainer
*
dataContainer
READ
dataContainer
WRITE
setDataContainer
NOTIFY
dataContainerChanged
)
Q_PROPERTY
(
bool
dirty
READ
dirty
NOTIFY
dirtyChanged
)
Q_PROPERTY
(
bool
syncronized
READ
syncronizedWithController
NOTIFY
syncronizedWithControllerChanged
)
// Property accessors
PlanMasterController
*
masterController
(
void
)
{
return
_masterController
;
}
...
...
@@ -72,7 +71,6 @@ public:
QStringList
saveNameFilters
(
void
)
const
;
QString
fileExtension
(
void
)
const
{
return
wimaFileExtension
;
}
QGeoCoordinate
joinedAreaCenter
(
void
)
const
;
bool
dirty
(
void
)
const
{
return
_dirty
;
}
WimaDataContainer
*
dataContainer
(
void
)
{
return
_container
;}
// Property setters
...
...
@@ -82,6 +80,9 @@ public:
void
setCurrentPolygonIndex
(
int
index
);
void
setDataContainer
(
WimaDataContainer
*
container
);
// Property acessors
bool
syncronizedWithController
();
// Member Methodes
Q_INVOKABLE
bool
addMeasurementArea
();
/// Removes an area from _visualItems
...
...
@@ -93,6 +94,8 @@ public:
Q_INVOKABLE
void
removeAll
();
/// Recalculates vehicle corridor, flight path, etc.
Q_INVOKABLE
bool
updateMission
();
/// Pushes the generated mission data to the container, for exchange with wimaController
Q_INVOKABLE
void
pushToContainer
();
Q_INVOKABLE
void
saveToCurrent
();
Q_INVOKABLE
void
saveToFile
(
const
QString
&
filename
);
...
...
@@ -112,29 +115,27 @@ public:
static
const
char
*
missionItemsName
;
signals:
void
masterControllerChanged
(
void
);
void
missionControllerChanged
(
void
);
void
visualItemsChanged
(
void
);
void
currentPolygonIndexChanged
(
int
index
);
void
currentFileChanged
();
void
dataContainerChanged
();
void
dirtyChanged
(
bool
dirty
);
void
masterControllerChanged
(
void
);
void
missionControllerChanged
(
void
);
void
visualItemsChanged
(
void
);
void
currentPolygonIndexChanged
(
int
index
);
void
currentFileChanged
();
void
dataContainerChanged
();
void
syncronizedWithControllerChanged
(
void
);
private
slots
:
void
recalcPolygonInteractivity
(
int
index
);
bool
calcArrivalAndReturnPath
(
void
);
bool
recalcJoinedArea
(
QString
&
errorString
);
void
pushToContainer
();
void
setDirtyTrue
();
void
recalcPolygonInteractivity
(
int
index
);
bool
calcArrivalAndReturnPath
(
void
);
bool
recalcJoinedArea
(
QString
&
errorString
);
// called by _updateTimer::timeout signal, updates different mission parts, if parameters (e.g. survey or areas) have changed
void
updateTimerSlot
();
void
updateTimerSlot
();
void
setSyncronizedWithControllerFalse
(
void
);
private:
// Member Functions
WimaPlanData
toPlanData
();
void
set
Dirty
(
bool
ready
);
void
set
SyncronizedWithController
(
bool
sync
);
// Member Variables
bool
_dirty
;
// set to true if updateMission() was sucessful, set to false if different parameters change
PlanMasterController
*
_masterController
;
MissionController
*
_missionController
;
int
_currentAreaIndex
;
...
...
@@ -153,4 +154,6 @@ private:
QTimer
_updateTimer
;
// on this timers timeout different mission parts will be updated, if parameters (e.g. survey or areas) have changed
QGeoCoordinate
_lastSurveyRefPoint
;
bool
_surveyRefChanging
;
bool
_syncronizedWithController
;
// true if planData is syncronized with wimaController
};
src/WimaView/WimaToolBar.qml
View file @
243a826b
...
...
@@ -285,17 +285,17 @@ Rectangle {
anchors.rightMargin
:
_margins
anchors.right
:
parent
.
right
anchors.verticalCenter
:
parent
.
verticalCenter
text
:
qsTr
(
"
Calculate
"
)
text
:
qsTr
(
"
Sync WiMA
"
)
enabled
:
true
visible
:
true
onClicked
:
wimaPlaner
.
updateMission
()
onClicked
:
wimaPlaner
.
pushToContainer
()
PropertyAnimation
on
opacity
{
easing.type
:
Easing
.
OutQuart
from
:
0.5
to
:
1
loops
:
Animation
.
Infinite
running
:
wimaPlaner
.
dirty
running
:
!
wimaPlaner
.
syncronized
alwaysRunToEnd
:
true
duration
:
2000
}
...
...
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