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
8484d079
Commit
8484d079
authored
May 14, 2017
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Takeoff uses PILOT_TAKEOFF_ALT and ui validation only
parent
120781ae
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
15 additions
and
10 deletions
+15
-10
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+15
-10
No files found.
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
8484d079
...
...
@@ -172,6 +172,20 @@ void ArduCopterFirmwarePlugin::guidedModeLand(Vehicle* vehicle)
void
ArduCopterFirmwarePlugin
::
guidedModeTakeoff
(
Vehicle
*
vehicle
)
{
QString
takeoffAltParam
(
"PILOT_TKOFF_ALT"
);
if
(
!
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
))
{
qgcApp
()
->
showMessage
(
tr
(
"Unable to takeoff, %1 parameter missing."
).
arg
(
takeoffAltParam
));
return
;
}
Fact
*
takeoffAltFact
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
takeoffAltParam
);
float
takeoffAlt
=
takeoffAltFact
->
rawValue
().
toDouble
();
if
(
takeoffAlt
<=
0
)
{
takeoffAlt
=
2.5
;
}
else
{
takeoffAlt
/=
100
;
// centimeters -> meters
}
if
(
!
_armVehicleAndValidate
(
vehicle
))
{
qgcApp
()
->
showMessage
(
tr
(
"Unable to takeoff: Vehicle failed to arm."
));
return
;
...
...
@@ -181,7 +195,7 @@ void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle)
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
,
2.5
);
takeoffAlt
);
}
void
ArduCopterFirmwarePlugin
::
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
...
...
@@ -203,15 +217,6 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
return
;
}
// Don't allow altitude to fall below 3 meters above home
double
currentAltRel
=
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
();
if
(
altitudeChange
<=
0
&&
currentAltRel
<=
3
)
{
return
;
}
if
(
currentAltRel
+
altitudeChange
<
3
)
{
altitudeChange
=
3
-
currentAltRel
;
}
setGuidedMode
(
vehicle
,
true
);
mavlink_message_t
msg
;
...
...
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