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
ff4c7e3d
Unverified
Commit
ff4c7e3d
authored
Sep 05, 2018
by
Don Gagne
Committed by
GitHub
Sep 05, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6851 from mavlink/plannedHomeAlt_3.4
Fix terrain NaN making it all the way to Planned Home altitude
parents
1bd2ba52
2c2808b0
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
5 additions
and
4 deletions
+5
-4
MissionController.cc
src/MissionManager/MissionController.cc
+3
-1
MissionSettingsItem.cc
src/MissionManager/MissionSettingsItem.cc
+2
-3
No files found.
src/MissionManager/MissionController.cc
View file @
ff4c7e3d
...
...
@@ -1533,7 +1533,9 @@ void MissionController::_setPlannedHomePositionFromFirstCoordinate(void)
VisualMissionItem
*
item
=
_visualItems
->
value
<
VisualMissionItem
*>
(
i
);
if
(
item
->
specifiesCoordinate
())
{
_settingsItem
->
setCoordinate
(
item
->
coordinate
().
atDistanceAndAzimuth
(
30
,
0
));
QGeoCoordinate
plannedHomeCoord
=
item
->
coordinate
().
atDistanceAndAzimuth
(
30
,
0
);
plannedHomeCoord
.
setAltitude
(
0
);
_settingsItem
->
setCoordinate
(
plannedHomeCoord
);
}
}
}
...
...
src/MissionManager/MissionSettingsItem.cc
View file @
ff4c7e3d
...
...
@@ -231,7 +231,7 @@ void MissionSettingsItem::setHomePositionFromVehicle(const QGeoCoordinate& coord
void
MissionSettingsItem
::
setCoordinate
(
const
QGeoCoordinate
&
coordinate
)
{
if
(
_plannedHomePositionCoordinate
!=
coordinate
)
{
// ArduPilot tends to send crap home positions at initial vehic
el
boot, discard them
// ArduPilot tends to send crap home positions at initial vehic
le
boot, discard them
if
(
coordinate
.
isValid
()
&&
(
coordinate
.
latitude
()
!=
0
||
coordinate
.
longitude
()
!=
0
))
{
_plannedHomePositionCoordinate
=
coordinate
;
emit
coordinateChanged
(
coordinate
);
...
...
@@ -269,7 +269,6 @@ void MissionSettingsItem::_updateAltitudeInCoordinate(QVariant value)
double
newAltitude
=
value
.
toDouble
();
if
(
!
qFuzzyCompare
(
_plannedHomePositionCoordinate
.
altitude
(),
newAltitude
))
{
_plannedHomePositionCoordinate
.
setAltitude
(
newAltitude
);
emit
coordinateChanged
(
_plannedHomePositionCoordinate
);
emit
exitCoordinateChanged
(
_plannedHomePositionCoordinate
);
...
...
@@ -295,7 +294,7 @@ void MissionSettingsItem::setMissionEndRTL(bool missionEndRTL)
void
MissionSettingsItem
::
_setHomeAltFromTerrain
(
double
terrainAltitude
)
{
if
(
!
_plannedHomePositionFromVehicle
)
{
if
(
!
_plannedHomePositionFromVehicle
&&
!
qIsNaN
(
terrainAltitude
)
)
{
_plannedHomePositionAltitudeFact
.
setRawValue
(
terrainAltitude
);
}
}
...
...
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