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
ab673bd9
Unverified
Commit
ab673bd9
authored
Oct 30, 2018
by
Don Gagne
Committed by
GitHub
Oct 30, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6965 from DonLakeFlyer/UpstreamStableMerge
Upstream stable merge
parents
6d622f4c
46f961b2
Changes
9
Hide whitespace changes
Inline
Side-by-side
Showing
9 changed files
with
55 additions
and
24 deletions
+55
-24
ChangeLog.md
ChangeLog.md
+7
-0
ParameterManager.cc
src/FactSystem/ParameterManager.cc
+5
-5
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+1
-1
GeoFenceController.cc
src/MissionManager/GeoFenceController.cc
+3
-2
MissionController.cc
src/MissionManager/MissionController.cc
+28
-8
MissionController.h
src/MissionManager/MissionController.h
+3
-2
MissionControllerTest.cc
src/MissionManager/MissionControllerTest.cc
+2
-3
StructureScan.SettingsGroup.json
src/MissionManager/StructureScan.SettingsGroup.json
+1
-0
StructureScanComplexItem.cc
src/MissionManager/StructureScanComplexItem.cc
+5
-3
No files found.
ChangeLog.md
View file @
ab673bd9
...
...
@@ -15,6 +15,13 @@ Note: This file only contains high level features or important fixes.
## 3.4
### 3.4.5 - Not yet released
*
Plan GeoFence: Fix loading of fence from intermediate 3.4 code
*
Orbit: Turn off for PX4 since still not supported
*
Structure Scan: Fix loading of structure scan height
*
ArduPilot: Fix location of planned home position when not connected to vehicle. Issue #6840.
*
Fix loading of parameters from multiple components. Would report download complete too early, thus missing all default component params.
### 3.4.4 - Stable
*
Stable desktop versions now inform user at boot if newer version is available.
*
Multi-Vehicle Start Mission and Pause now work correctly. Issue #6864.
...
...
src/FactSystem/ParameterManager.cc
View file @
ab673bd9
...
...
@@ -347,12 +347,12 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
// Add meta data to default component. We need to do this before we setup the group map since group
// map requires meta data.
_addMetaDataToDefaultComponent
();
}
// When we are getting the very last component param index, reset the group maps to update for the
// new params. By handling this here, we can pick up components which finish up later than the default
// component param set.
_setupCategoryMap
();
// When we are getting the very last component param index, reset the group maps to update for the
// new params. By handling this here, we can pick up components which finish up later than the default
// component param set.
_setupCategoryMap
();
}
}
// Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
ab673bd9
...
...
@@ -233,7 +233,7 @@ bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities c
{
int
available
=
SetFlightModeCapability
|
PauseVehicleCapability
|
GuidedModeCapability
;
if
(
vehicle
->
multiRotor
()
||
vehicle
->
vtol
())
{
available
|=
TakeoffVehicleCapability
|
OrbitModeCapability
;
available
|=
TakeoffVehicleCapability
;
}
return
(
capabilities
&
available
)
==
capabilities
;
...
...
src/MissionManager/GeoFenceController.cc
View file @
ab673bd9
...
...
@@ -123,8 +123,9 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString)
errorString
.
clear
();
if
(
json
.
contains
(
JsonHelper
::
jsonVersionKey
)
&&
json
[
JsonHelper
::
jsonVersionKey
].
toInt
()
==
1
)
{
// We just ignore old version 1 data
if
(
!
json
.
contains
(
JsonHelper
::
jsonVersionKey
)
||
(
json
.
contains
(
JsonHelper
::
jsonVersionKey
)
&&
json
[
JsonHelper
::
jsonVersionKey
].
toInt
()
==
1
))
{
// We just ignore old version 1 or prior data
return
true
;
}
...
...
src/MissionManager/MissionController.cc
View file @
ab673bd9
...
...
@@ -375,7 +375,9 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
newItem
->
setMissionFlightStatus
(
_missionFlightStatus
);
_visualItems
->
insert
(
i
,
newItem
);
_recalcAll
();
// We send the click coordinate through here to be able to set the planned home position from the user click location if needed
_recalcAllWithClickCoordinate
(
coordinate
);
return
newItem
->
sequenceNumber
();
}
...
...
@@ -1526,8 +1528,10 @@ void MissionController::_recalcChildItems(void)
}
}
void
MissionController
::
_setPlannedHomePositionFromFirstCoordinate
(
void
)
void
MissionController
::
_setPlannedHomePositionFromFirstCoordinate
(
const
QGeoCoordinate
&
clickCoordinate
)
{
QGeoCoordinate
firstCoordinate
;
if
(
_settingsItem
->
coordinate
().
isValid
())
{
return
;
}
...
...
@@ -1537,18 +1541,28 @@ void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
VisualMissionItem
*
item
=
_visualItems
->
value
<
VisualMissionItem
*>
(
i
);
if
(
item
->
specifiesCoordinate
())
{
QGeoCoordinate
plannedHomeCoord
=
item
->
coordinate
().
atDistanceAndAzimuth
(
30
,
0
);
plannedHomeCoord
.
setAltitude
(
0
);
_settingsItem
->
setCoordinate
(
plannedHomeCoord
);
firstCoordinate
=
item
->
coordinate
();
break
;
}
}
}
// No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
if
(
!
firstCoordinate
.
isValid
())
{
firstCoordinate
=
clickCoordinate
;
}
void
MissionController
::
_recalcAll
(
void
)
if
(
firstCoordinate
.
isValid
())
{
QGeoCoordinate
plannedHomeCoord
=
firstCoordinate
.
atDistanceAndAzimuth
(
30
,
0
);
plannedHomeCoord
.
setAltitude
(
0
);
_settingsItem
->
setCoordinate
(
plannedHomeCoord
);
}
}
/// @param clickCoordinate The location of the user click when inserting a new item
void
MissionController
::
_recalcAllWithClickCoordinate
(
QGeoCoordinate
&
clickCoordinate
)
{
if
(
!
_flyView
)
{
_setPlannedHomePositionFromFirstCoordinate
();
_setPlannedHomePositionFromFirstCoordinate
(
clickCoordinate
);
}
_recalcSequence
();
_recalcChildItems
();
...
...
@@ -1556,6 +1570,12 @@ void MissionController::_recalcAll(void)
_updateTimer
.
start
(
UPDATE_TIMEOUT
);
}
void
MissionController
::
_recalcAll
(
void
)
{
QGeoCoordinate
emptyCoord
;
_recalcAllWithClickCoordinate
(
emptyCoord
);
}
/// Initializes a new set of mission items
void
MissionController
::
_initAllVisualItems
(
void
)
{
...
...
src/MissionManager/MissionController.h
View file @
ab673bd9
...
...
@@ -234,12 +234,13 @@ private slots:
void
_managerRemoveAllComplete
(
bool
error
);
void
_updateTimeout
();
void
_complexBoundingBoxChanged
();
void
_recalcAll
(
void
);
private:
void
_init
(
void
);
void
_recalcSequence
(
void
);
void
_recalcChildItems
(
void
);
void
_recalcAll
(
void
);
void
_recalcAll
WithClickCoordinate
(
QGeoCoordinate
&
clickCoordinate
);
void
_initAllVisualItems
(
void
);
void
_deinitAllVisualItems
(
void
);
void
_initVisualItem
(
VisualMissionItem
*
item
);
...
...
@@ -258,7 +259,7 @@ private:
int
_nextSequenceNumber
(
void
);
void
_scanForAdditionalSettings
(
QmlObjectListModel
*
visualItems
,
Vehicle
*
vehicle
);
static
bool
_convertToMissionItems
(
QmlObjectListModel
*
visualMissionItems
,
QList
<
MissionItem
*>&
rgMissionItems
,
QObject
*
missionItemParent
);
void
_setPlannedHomePositionFromFirstCoordinate
(
void
);
void
_setPlannedHomePositionFromFirstCoordinate
(
const
QGeoCoordinate
&
clickCoordinate
);
void
_resetMissionFlightStatus
(
void
);
void
_addHoverTime
(
double
hoverTime
,
double
hoverDistance
,
int
waypointIndex
);
void
_addCruiseTime
(
double
cruiseTime
,
double
cruiseDistance
,
int
wayPointIndex
);
...
...
src/MissionManager/MissionControllerTest.cc
View file @
ab673bd9
...
...
@@ -135,9 +135,8 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
QCOMPARE
((
MAV_CMD
)
simpleItem
->
command
(),
MAV_CMD_NAV_TAKEOFF
);
QCOMPARE
(
simpleItem
->
childItems
()
->
count
(),
0
);
// If the first item added specifies a coordinate, then planned home position will be set
bool
plannedHomePositionValue
=
firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
?
false
:
true
;
QCOMPARE
(
settingsItem
->
coordinate
().
isValid
(),
plannedHomePositionValue
);
// Planned home position should always be set after first item
QVERIFY
(
settingsItem
->
coordinate
().
isValid
());
// ArduPilot takeoff command has no coordinate, so should be child item
QCOMPARE
(
settingsItem
->
childItems
()
->
count
(),
firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
?
1
:
0
);
...
...
src/MissionManager/StructureScan.SettingsGroup.json
View file @
ab673bd9
...
...
@@ -28,6 +28,7 @@
"name"
:
"StructureHeight"
,
"shortDescription"
:
"Height of structure being scanned."
,
"type"
:
"double"
,
"decimalPlaces"
:
2
,
"units"
:
"m"
,
"min"
:
1
,
"defaultValue"
:
100
...
...
src/MissionManager/StructureScanComplexItem.cc
View file @
ab673bd9
...
...
@@ -215,9 +215,11 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
return
false
;
}
_altitudeFact
.
setRawValue
(
complexObject
[
altitudeName
].
toDouble
());
_layersFact
.
setRawValue
(
complexObject
[
layersName
].
toDouble
());
_altitudeRelative
=
complexObject
[
_jsonAltitudeRelativeKey
].
toBool
(
true
);
_altitudeFact
.
setRawValue
(
complexObject
[
altitudeName
].
toDouble
());
_layersFact
.
setRawValue
(
complexObject
[
layersName
].
toDouble
());
_structureHeightFact
.
setRawValue
(
complexObject
[
structureHeightName
].
toDouble
());
_altitudeRelative
=
complexObject
[
_jsonAltitudeRelativeKey
].
toBool
(
true
);
double
gimbalPitchValue
=
0
;
if
(
complexObject
.
contains
(
gimbalPitchName
))
{
...
...
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