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
004bda50
Commit
004bda50
authored
Dec 08, 2016
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Correct guided mode AMSL versus Relative handling
parent
099fe046
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
2 additions
and
7 deletions
+2
-7
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+1
-6
FlightDisplayViewWidgets.qml
src/FlightDisplay/FlightDisplayViewWidgets.qml
+1
-1
No files found.
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
004bda50
...
...
@@ -120,16 +120,11 @@ void ArduCopterFirmwarePlugin::guidedModeLand(Vehicle* vehicle)
void
ArduCopterFirmwarePlugin
::
guidedModeTakeoff
(
Vehicle
*
vehicle
,
double
altitudeRel
)
{
if
(
qIsNaN
(
vehicle
->
altitudeAMSL
()
->
rawValue
().
toDouble
()))
{
qgcApp
()
->
showMessage
(
QStringLiteral
(
"Unable to takeoff, vehicle position not known."
));
return
;
}
vehicle
->
sendMavCommand
(
vehicle
->
defaultComponentId
(),
MAV_CMD_NAV_TAKEOFF
,
true
,
// show error
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
,
vehicle
->
altitudeAMSL
()
->
rawValue
().
toFloat
()
+
altitudeRel
);
// AMSL meters
altitudeRel
);
}
void
ArduCopterFirmwarePlugin
::
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
...
...
src/FlightDisplay/FlightDisplayViewWidgets.qml
View file @
004bda50
...
...
@@ -437,7 +437,7 @@ Item {
break
;
case
confirmChangeAlt
:
altitudeSlider
.
visible
=
true
altitudeSlider
.
setInitialValueAppSettingsDistanceUnits
(
_activeVehicle
.
altitude
AMSL
.
value
)
altitudeSlider
.
setInitialValueAppSettingsDistanceUnits
(
_activeVehicle
.
altitude
Relative
.
value
)
guidedModeConfirm
.
confirmText
=
qsTr
(
"
change altitude
"
)
break
;
case
confirmGoTo
:
...
...
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