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
305b1a08
Commit
305b1a08
authored
Apr 22, 2017
by
Don Gagne
Committed by
GitHub
Apr 22, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #5040 from DonLakeFlyer/PlanSync
Plan: Sequential upload/down of individual managers
parents
987e776c
0fbfd43e
Changes
10
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
66 additions
and
25 deletions
+66
-25
APMGeoFenceManager.cc
src/FirmwarePlugin/APM/APMGeoFenceManager.cc
+1
-1
GeoFenceController.cc
src/MissionManager/GeoFenceController.cc
+0
-4
GeoFenceManager.cc
src/MissionManager/GeoFenceManager.cc
+2
-2
MissionController.cc
src/MissionManager/MissionController.cc
+5
-2
MissionManager.cc
src/MissionManager/MissionManager.cc
+4
-1
PlanMasterController.cc
src/MissionManager/PlanMasterController.cc
+45
-10
PlanMasterController.h
src/MissionManager/PlanMasterController.h
+6
-0
RallyPointController.cc
src/MissionManager/RallyPointController.cc
+0
-3
RallyPointManager.cc
src/MissionManager/RallyPointManager.cc
+2
-1
RallyPointManager.h
src/MissionManager/RallyPointManager.h
+1
-1
No files found.
src/FirmwarePlugin/APM/APMGeoFenceManager.cc
View file @
305b1a08
...
@@ -132,7 +132,7 @@ void APMGeoFenceManager::loadFromVehicle(void)
...
@@ -132,7 +132,7 @@ void APMGeoFenceManager::loadFromVehicle(void)
_requestFencePoint
(
_currentFencePoint
);
_requestFencePoint
(
_currentFencePoint
);
}
}
/// Called when a new mavlink message for ou
t
vehicle is received
/// Called when a new mavlink message for ou
r
vehicle is received
void
APMGeoFenceManager
::
_mavlinkMessageReceived
(
const
mavlink_message_t
&
message
)
void
APMGeoFenceManager
::
_mavlinkMessageReceived
(
const
mavlink_message_t
&
message
)
{
{
if
(
message
.
msgid
==
MAVLINK_MSG_ID_FENCE_POINT
)
{
if
(
message
.
msgid
==
MAVLINK_MSG_ID_FENCE_POINT
)
{
...
...
src/MissionManager/GeoFenceController.cc
View file @
305b1a08
...
@@ -107,10 +107,6 @@ void GeoFenceController::managerVehicleChanged(Vehicle* managerVehicle)
...
@@ -107,10 +107,6 @@ void GeoFenceController::managerVehicleChanged(Vehicle* managerVehicle)
connect
(
_geoFenceManager
,
&
GeoFenceManager
::
loadComplete
,
this
,
&
GeoFenceController
::
_loadComplete
);
connect
(
_geoFenceManager
,
&
GeoFenceManager
::
loadComplete
,
this
,
&
GeoFenceController
::
_loadComplete
);
connect
(
_geoFenceManager
,
&
GeoFenceManager
::
inProgressChanged
,
this
,
&
GeoFenceController
::
syncInProgressChanged
);
connect
(
_geoFenceManager
,
&
GeoFenceManager
::
inProgressChanged
,
this
,
&
GeoFenceController
::
syncInProgressChanged
);
if
(
!
_geoFenceManager
->
inProgress
())
{
_loadComplete
(
_geoFenceManager
->
breachReturnPoint
(),
_geoFenceManager
->
polygon
());
}
_signalAll
();
_signalAll
();
}
}
...
...
src/MissionManager/GeoFenceManager.cc
View file @
305b1a08
...
@@ -40,8 +40,8 @@ void GeoFenceManager::loadFromVehicle(void)
...
@@ -40,8 +40,8 @@ void GeoFenceManager::loadFromVehicle(void)
void
GeoFenceManager
::
sendToVehicle
(
const
QGeoCoordinate
&
breachReturn
,
QmlObjectListModel
&
polygon
)
void
GeoFenceManager
::
sendToVehicle
(
const
QGeoCoordinate
&
breachReturn
,
QmlObjectListModel
&
polygon
)
{
{
// No geofence support in unknown vehicle
Q_UNUSED
(
breachReturn
);
Q_UNUSED
(
breachReturn
);
Q_UNUSED
(
polygon
);
Q_UNUSED
(
polygon
);
emit
loadComplete
(
QGeoCoordinate
(),
QList
<
QGeoCoordinate
>
());
// No geofence support in unknown vehicle
}
}
src/MissionManager/MissionController.cc
View file @
305b1a08
...
@@ -446,8 +446,11 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
...
@@ -446,8 +446,11 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
// Mission Settings
// Mission Settings
AppSettings
*
appSettings
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
();
AppSettings
*
appSettings
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
();
appSettings
->
offlineEditingFirmwareType
()
->
setRawValue
(
AppSettings
::
offlineEditingFirmwareTypeFromFirmwareType
((
MAV_AUTOPILOT
)
json
[
_jsonVehicleTypeKey
].
toInt
()));
if
(
_masterController
->
offline
())
{
appSettings
->
offlineEditingVehicleType
()
->
setRawValue
(
AppSettings
::
offlineEditingVehicleTypeFromVehicleType
((
MAV_TYPE
)
json
[
_jsonVehicleTypeKey
].
toInt
()));
// We only update if offline since if we are online we use the online vehicle settings
appSettings
->
offlineEditingFirmwareType
()
->
setRawValue
(
AppSettings
::
offlineEditingFirmwareTypeFromFirmwareType
((
MAV_AUTOPILOT
)
json
[
_jsonVehicleTypeKey
].
toInt
()));
appSettings
->
offlineEditingVehicleType
()
->
setRawValue
(
AppSettings
::
offlineEditingVehicleTypeFromVehicleType
((
MAV_TYPE
)
json
[
_jsonVehicleTypeKey
].
toInt
()));
}
if
(
json
.
contains
(
_jsonCruiseSpeedKey
))
{
if
(
json
.
contains
(
_jsonCruiseSpeedKey
))
{
appSettings
->
offlineEditingCruiseSpeed
()
->
setRawValue
(
json
[
_jsonCruiseSpeedKey
].
toDouble
());
appSettings
->
offlineEditingCruiseSpeed
()
->
setRawValue
(
json
[
_jsonCruiseSpeedKey
].
toDouble
());
}
}
...
...
src/MissionManager/MissionManager.cc
View file @
305b1a08
...
@@ -48,7 +48,6 @@ void MissionManager::_writeMissionItemsWorker(void)
...
@@ -48,7 +48,6 @@ void MissionManager::_writeMissionItemsWorker(void)
{
{
_lastMissionRequest
=
-
1
;
_lastMissionRequest
=
-
1
;
emit
newMissionItemsAvailable
(
_missionItems
.
count
()
==
0
);
emit
progressPct
(
0
);
emit
progressPct
(
0
);
qCDebug
(
MissionManagerLog
)
<<
"writeMissionItems count:"
<<
_missionItems
.
count
();
qCDebug
(
MissionManagerLog
)
<<
"writeMissionItems count:"
<<
_missionItems
.
count
();
...
@@ -870,6 +869,10 @@ void MissionManager::_finishTransaction(bool success)
...
@@ -870,6 +869,10 @@ void MissionManager::_finishTransaction(bool success)
emit
newMissionItemsAvailable
(
false
);
emit
newMissionItemsAvailable
(
false
);
}
}
if
(
_transactionInProgress
==
TransactionWrite
)
{
emit
newMissionItemsAvailable
(
_missionItems
.
count
()
==
0
);
}
_itemIndicesToRead
.
clear
();
_itemIndicesToRead
.
clear
();
_itemIndicesToWrite
.
clear
();
_itemIndicesToWrite
.
clear
();
...
...
src/MissionManager/PlanMasterController.cc
View file @
305b1a08
...
@@ -13,6 +13,7 @@
...
@@ -13,6 +13,7 @@
#include "SettingsManager.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "AppSettings.h"
#include "JsonHelper.h"
#include "JsonHelper.h"
#include "MissionManager.h"
#include <QJsonDocument>
#include <QJsonDocument>
#include <QFileInfo>
#include <QFileInfo>
...
@@ -33,6 +34,10 @@ PlanMasterController::PlanMasterController(QObject* parent)
...
@@ -33,6 +34,10 @@ PlanMasterController::PlanMasterController(QObject* parent)
,
_missionController
(
this
)
,
_missionController
(
this
)
,
_geoFenceController
(
this
)
,
_geoFenceController
(
this
)
,
_rallyPointController
(
this
)
,
_rallyPointController
(
this
)
,
_loadGeoFence
(
false
)
,
_loadRallyPoints
(
false
)
,
_sendGeoFence
(
false
)
,
_sendRallyPoints
(
false
)
{
{
connect
(
&
_missionController
,
&
MissionController
::
dirtyChanged
,
this
,
&
PlanMasterController
::
dirtyChanged
);
connect
(
&
_missionController
,
&
MissionController
::
dirtyChanged
,
this
,
&
PlanMasterController
::
dirtyChanged
);
connect
(
&
_geoFenceController
,
&
GeoFenceController
::
dirtyChanged
,
this
,
&
PlanMasterController
::
dirtyChanged
);
connect
(
&
_geoFenceController
,
&
GeoFenceController
::
dirtyChanged
,
this
,
&
PlanMasterController
::
dirtyChanged
);
...
@@ -82,9 +87,17 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
...
@@ -82,9 +87,17 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
_managerVehicle
=
_controllerVehicle
;
_managerVehicle
=
_controllerVehicle
;
newOffline
=
true
;
newOffline
=
true
;
}
else
{
}
else
{
// FIXME: Check for vehicle compatibility. (edit mode only)
_managerVehicle
=
activeVehicle
;
newOffline
=
false
;
newOffline
=
false
;
_managerVehicle
=
activeVehicle
;
// Update controllerVehicle to the currently connected vehicle
AppSettings
*
appSettings
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
();
appSettings
->
offlineEditingFirmwareType
()
->
setRawValue
(
AppSettings
::
offlineEditingFirmwareTypeFromFirmwareType
(
_managerVehicle
->
firmwareType
()));
appSettings
->
offlineEditingVehicleType
()
->
setRawValue
(
AppSettings
::
offlineEditingVehicleTypeFromVehicleType
(
_managerVehicle
->
vehicleType
()));
// We use these signals to sequence upload and download to the multiple controller/managers
connect
(
_managerVehicle
->
missionManager
(),
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
PlanMasterController
::
_loadSendMissionComplete
);
connect
(
_managerVehicle
->
geoFenceManager
(),
&
GeoFenceManager
::
loadComplete
,
this
,
&
PlanMasterController
::
_loadSendGeoFenceCompelte
);
}
}
if
(
newOffline
!=
_offline
)
{
if
(
newOffline
!=
_offline
)
{
_offline
=
newOffline
;
_offline
=
newOffline
;
...
@@ -106,23 +119,46 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
...
@@ -106,23 +119,46 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
void
PlanMasterController
::
loadFromVehicle
(
void
)
void
PlanMasterController
::
loadFromVehicle
(
void
)
{
{
// FIXME: Hack implementation
_loadGeoFence
=
true
;
_missionController
.
loadFromVehicle
();
_missionController
.
loadFromVehicle
();
_geoFenceController
.
loadFromVehicle
();
_rallyPointController
.
loadFromVehicle
();
setDirty
(
false
);
setDirty
(
false
);
}
}
void
PlanMasterController
::
_loadSendMissionComplete
(
void
)
{
if
(
_loadGeoFence
)
{
_loadGeoFence
=
false
;
_loadRallyPoints
=
true
;
_geoFenceController
.
loadFromVehicle
();
setDirty
(
false
);
}
else
if
(
_sendGeoFence
)
{
_sendGeoFence
=
false
;
_sendRallyPoints
=
true
;
_geoFenceController
.
sendToVehicle
();
setDirty
(
false
);
}
}
void
PlanMasterController
::
_loadSendGeoFenceCompelte
(
void
)
{
if
(
_loadRallyPoints
)
{
_loadRallyPoints
=
false
;
_rallyPointController
.
loadFromVehicle
();
setDirty
(
false
);
}
else
if
(
_sendRallyPoints
)
{
_sendRallyPoints
=
false
;
_rallyPointController
.
sendToVehicle
();
}
}
void
PlanMasterController
::
sendToVehicle
(
void
)
void
PlanMasterController
::
sendToVehicle
(
void
)
{
{
// FIXME: Hack implementation
_sendGeoFence
=
true
;
_missionController
.
sendToVehicle
();
_missionController
.
sendToVehicle
();
_geoFenceController
.
sendToVehicle
();
_rallyPointController
.
sendToVehicle
();
setDirty
(
false
);
setDirty
(
false
);
}
}
void
PlanMasterController
::
loadFromFile
(
const
QString
&
filename
)
void
PlanMasterController
::
loadFromFile
(
const
QString
&
filename
)
{
{
QString
errorString
;
QString
errorString
;
...
@@ -291,4 +327,3 @@ void PlanMasterController::sendPlanToVehicle(Vehicle* vehicle, const QString& fi
...
@@ -291,4 +327,3 @@ void PlanMasterController::sendPlanToVehicle(Vehicle* vehicle, const QString& fi
controller
->
loadFromFile
(
filename
);
controller
->
loadFromFile
(
filename
);
delete
controller
;
delete
controller
;
}
}
src/MissionManager/PlanMasterController.h
View file @
305b1a08
...
@@ -83,6 +83,8 @@ signals:
...
@@ -83,6 +83,8 @@ signals:
private
slots
:
private
slots
:
void
_activeVehicleChanged
(
Vehicle
*
activeVehicle
);
void
_activeVehicleChanged
(
Vehicle
*
activeVehicle
);
void
_loadSendMissionComplete
(
void
);
void
_loadSendGeoFenceCompelte
(
void
);
private:
private:
MultiVehicleManager
*
_multiVehicleMgr
;
MultiVehicleManager
*
_multiVehicleMgr
;
...
@@ -93,6 +95,10 @@ private:
...
@@ -93,6 +95,10 @@ private:
MissionController
_missionController
;
MissionController
_missionController
;
GeoFenceController
_geoFenceController
;
GeoFenceController
_geoFenceController
;
RallyPointController
_rallyPointController
;
RallyPointController
_rallyPointController
;
bool
_loadGeoFence
;
bool
_loadRallyPoints
;
bool
_sendGeoFence
;
bool
_sendRallyPoints
;
static
const
int
_planFileVersion
;
static
const
int
_planFileVersion
;
static
const
char
*
_planFileType
;
static
const
char
*
_planFileType
;
...
...
src/MissionManager/RallyPointController.cc
View file @
305b1a08
...
@@ -70,9 +70,6 @@ void RallyPointController::managerVehicleChanged(Vehicle* managerVehicle)
...
@@ -70,9 +70,6 @@ void RallyPointController::managerVehicleChanged(Vehicle* managerVehicle)
connect
(
_rallyPointManager
,
&
RallyPointManager
::
loadComplete
,
this
,
&
RallyPointController
::
_loadComplete
);
connect
(
_rallyPointManager
,
&
RallyPointManager
::
loadComplete
,
this
,
&
RallyPointController
::
_loadComplete
);
connect
(
_rallyPointManager
,
&
RallyPointManager
::
inProgressChanged
,
this
,
&
RallyPointController
::
syncInProgressChanged
);
connect
(
_rallyPointManager
,
&
RallyPointManager
::
inProgressChanged
,
this
,
&
RallyPointController
::
syncInProgressChanged
);
if
(
!
syncInProgress
())
{
_loadComplete
(
_rallyPointManager
->
points
());
}
emit
rallyPointsSupportedChanged
(
rallyPointsSupported
());
emit
rallyPointsSupportedChanged
(
rallyPointsSupported
());
}
}
...
...
src/MissionManager/RallyPointManager.cc
View file @
305b1a08
...
@@ -39,6 +39,7 @@ void RallyPointManager::loadFromVehicle(void)
...
@@ -39,6 +39,7 @@ void RallyPointManager::loadFromVehicle(void)
void
RallyPointManager
::
sendToVehicle
(
const
QList
<
QGeoCoordinate
>&
rgPoints
)
void
RallyPointManager
::
sendToVehicle
(
const
QList
<
QGeoCoordinate
>&
rgPoints
)
{
{
Q_UNUSED
(
rgPoints
);
// No support in generic vehicle
// No support in generic vehicle
Q_UNUSED
(
rgPoints
);
emit
loadComplete
(
QList
<
QGeoCoordinate
>
());
}
}
src/MissionManager/RallyPointManager.h
View file @
305b1a08
...
@@ -58,7 +58,7 @@ signals:
...
@@ -58,7 +58,7 @@ signals:
void
loadComplete
(
const
QList
<
QGeoCoordinate
>
rgPoints
);
void
loadComplete
(
const
QList
<
QGeoCoordinate
>
rgPoints
);
void
inProgressChanged
(
bool
inProgress
);
void
inProgressChanged
(
bool
inProgress
);
void
error
(
int
errorCode
,
const
QString
&
errorMsg
);
void
error
(
int
errorCode
,
const
QString
&
errorMsg
);
protected:
protected:
void
_sendError
(
ErrorCode_t
errorCode
,
const
QString
&
errorMsg
);
void
_sendError
(
ErrorCode_t
errorCode
,
const
QString
&
errorMsg
);
...
...
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