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
0fbfd43e
Commit
0fbfd43e
authored
Apr 21, 2017
by
Don Gagne
Browse files
Sequential upload/down of individual managers
parent
987e776c
Changes
10
Hide whitespace changes
Inline
Side-by-side
src/FirmwarePlugin/APM/APMGeoFenceManager.cc
View file @
0fbfd43e
...
...
@@ -132,7 +132,7 @@ void APMGeoFenceManager::loadFromVehicle(void)
_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
)
{
if
(
message
.
msgid
==
MAVLINK_MSG_ID_FENCE_POINT
)
{
...
...
src/MissionManager/GeoFenceController.cc
View file @
0fbfd43e
...
...
@@ -107,10 +107,6 @@ void GeoFenceController::managerVehicleChanged(Vehicle* managerVehicle)
connect
(
_geoFenceManager
,
&
GeoFenceManager
::
loadComplete
,
this
,
&
GeoFenceController
::
_loadComplete
);
connect
(
_geoFenceManager
,
&
GeoFenceManager
::
inProgressChanged
,
this
,
&
GeoFenceController
::
syncInProgressChanged
);
if
(
!
_geoFenceManager
->
inProgress
())
{
_loadComplete
(
_geoFenceManager
->
breachReturnPoint
(),
_geoFenceManager
->
polygon
());
}
_signalAll
();
}
...
...
src/MissionManager/GeoFenceManager.cc
View file @
0fbfd43e
...
...
@@ -40,8 +40,8 @@ void GeoFenceManager::loadFromVehicle(void)
void
GeoFenceManager
::
sendToVehicle
(
const
QGeoCoordinate
&
breachReturn
,
QmlObjectListModel
&
polygon
)
{
// No geofence support in unknown vehicle
Q_UNUSED
(
breachReturn
);
Q_UNUSED
(
polygon
);
// No geofence support in unknown vehicle
emit
loadComplete
(
QGeoCoordinate
(),
QList
<
QGeoCoordinate
>
());
}
src/MissionManager/MissionController.cc
View file @
0fbfd43e
...
...
@@ -446,8 +446,11 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
// Mission Settings
AppSettings
*
appSettings
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
();
appSettings
->
offlineEditingFirmwareType
()
->
setRawValue
(
AppSettings
::
offlineEditingFirmwareTypeFromFirmwareType
((
MAV_AUTOPILOT
)
json
[
_jsonVehicleTypeKey
].
toInt
()));
appSettings
->
offlineEditingVehicleType
()
->
setRawValue
(
AppSettings
::
offlineEditingVehicleTypeFromVehicleType
((
MAV_TYPE
)
json
[
_jsonVehicleTypeKey
].
toInt
()));
if
(
_masterController
->
offline
())
{
// 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
))
{
appSettings
->
offlineEditingCruiseSpeed
()
->
setRawValue
(
json
[
_jsonCruiseSpeedKey
].
toDouble
());
}
...
...
src/MissionManager/MissionManager.cc
View file @
0fbfd43e
...
...
@@ -48,7 +48,6 @@ void MissionManager::_writeMissionItemsWorker(void)
{
_lastMissionRequest
=
-
1
;
emit
newMissionItemsAvailable
(
_missionItems
.
count
()
==
0
);
emit
progressPct
(
0
);
qCDebug
(
MissionManagerLog
)
<<
"writeMissionItems count:"
<<
_missionItems
.
count
();
...
...
@@ -870,6 +869,10 @@ void MissionManager::_finishTransaction(bool success)
emit
newMissionItemsAvailable
(
false
);
}
if
(
_transactionInProgress
==
TransactionWrite
)
{
emit
newMissionItemsAvailable
(
_missionItems
.
count
()
==
0
);
}
_itemIndicesToRead
.
clear
();
_itemIndicesToWrite
.
clear
();
...
...
src/MissionManager/PlanMasterController.cc
View file @
0fbfd43e
...
...
@@ -13,6 +13,7 @@
#include
"SettingsManager.h"
#include
"AppSettings.h"
#include
"JsonHelper.h"
#include
"MissionManager.h"
#include
<QJsonDocument>
#include
<QFileInfo>
...
...
@@ -33,6 +34,10 @@ PlanMasterController::PlanMasterController(QObject* parent)
,
_missionController
(
this
)
,
_geoFenceController
(
this
)
,
_rallyPointController
(
this
)
,
_loadGeoFence
(
false
)
,
_loadRallyPoints
(
false
)
,
_sendGeoFence
(
false
)
,
_sendRallyPoints
(
false
)
{
connect
(
&
_missionController
,
&
MissionController
::
dirtyChanged
,
this
,
&
PlanMasterController
::
dirtyChanged
);
connect
(
&
_geoFenceController
,
&
GeoFenceController
::
dirtyChanged
,
this
,
&
PlanMasterController
::
dirtyChanged
);
...
...
@@ -82,9 +87,17 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
_managerVehicle
=
_controllerVehicle
;
newOffline
=
true
;
}
else
{
// FIXME: Check for vehicle compatibility. (edit mode only)
_managerVehicle
=
activeVehicle
;
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
)
{
_offline
=
newOffline
;
...
...
@@ -106,23 +119,46 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
void
PlanMasterController
::
loadFromVehicle
(
void
)
{
// FIXME: Hack implementation
_loadGeoFence
=
true
;
_missionController
.
loadFromVehicle
();
_geoFenceController
.
loadFromVehicle
();
_rallyPointController
.
loadFromVehicle
();
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
)
{
// FIXME: Hack implementation
_sendGeoFence
=
true
;
_missionController
.
sendToVehicle
();
_geoFenceController
.
sendToVehicle
();
_rallyPointController
.
sendToVehicle
();
setDirty
(
false
);
}
void
PlanMasterController
::
loadFromFile
(
const
QString
&
filename
)
{
QString
errorString
;
...
...
@@ -291,4 +327,3 @@ void PlanMasterController::sendPlanToVehicle(Vehicle* vehicle, const QString& fi
controller
->
loadFromFile
(
filename
);
delete
controller
;
}
src/MissionManager/PlanMasterController.h
View file @
0fbfd43e
...
...
@@ -83,6 +83,8 @@ signals:
private
slots
:
void
_activeVehicleChanged
(
Vehicle
*
activeVehicle
);
void
_loadSendMissionComplete
(
void
);
void
_loadSendGeoFenceCompelte
(
void
);
private:
MultiVehicleManager
*
_multiVehicleMgr
;
...
...
@@ -93,6 +95,10 @@ private:
MissionController
_missionController
;
GeoFenceController
_geoFenceController
;
RallyPointController
_rallyPointController
;
bool
_loadGeoFence
;
bool
_loadRallyPoints
;
bool
_sendGeoFence
;
bool
_sendRallyPoints
;
static
const
int
_planFileVersion
;
static
const
char
*
_planFileType
;
...
...
src/MissionManager/RallyPointController.cc
View file @
0fbfd43e
...
...
@@ -70,9 +70,6 @@ void RallyPointController::managerVehicleChanged(Vehicle* managerVehicle)
connect
(
_rallyPointManager
,
&
RallyPointManager
::
loadComplete
,
this
,
&
RallyPointController
::
_loadComplete
);
connect
(
_rallyPointManager
,
&
RallyPointManager
::
inProgressChanged
,
this
,
&
RallyPointController
::
syncInProgressChanged
);
if
(
!
syncInProgress
())
{
_loadComplete
(
_rallyPointManager
->
points
());
}
emit
rallyPointsSupportedChanged
(
rallyPointsSupported
());
}
...
...
src/MissionManager/RallyPointManager.cc
View file @
0fbfd43e
...
...
@@ -39,6 +39,7 @@ void RallyPointManager::loadFromVehicle(void)
void
RallyPointManager
::
sendToVehicle
(
const
QList
<
QGeoCoordinate
>&
rgPoints
)
{
Q_UNUSED
(
rgPoints
);
// No support in generic vehicle
Q_UNUSED
(
rgPoints
);
emit
loadComplete
(
QList
<
QGeoCoordinate
>
());
}
src/MissionManager/RallyPointManager.h
View file @
0fbfd43e
...
...
@@ -58,7 +58,7 @@ signals:
void
loadComplete
(
const
QList
<
QGeoCoordinate
>
rgPoints
);
void
inProgressChanged
(
bool
inProgress
);
void
error
(
int
errorCode
,
const
QString
&
errorMsg
);
protected:
void
_sendError
(
ErrorCode_t
errorCode
,
const
QString
&
errorMsg
);
...
...
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