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
8a23979e
Commit
8a23979e
authored
Sep 27, 2017
by
Don Gagne
Committed by
GitHub
Sep 27, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #5709 from DonLakeFlyer/QuadPlaneTakeoff
Fix QuadPlane takeoff
parents
59e12b8d
3124cb13
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
11 additions
and
6 deletions
+11
-6
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+11
-6
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
8a23979e
...
...
@@ -162,12 +162,10 @@ bool APMFirmwarePlugin::isCapable(const Vehicle* vehicle, FirmwareCapabilities c
uint32_t
available
=
SetFlightModeCapability
|
PauseVehicleCapability
|
GuidedModeCapability
;
if
(
vehicle
->
multiRotor
())
{
available
|=
TakeoffVehicleCapability
;
}
else
if
(
vehicle
->
fixedWing
())
{
// Quad plane supports takeoff
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"Q_ENABLE"
))
&&
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"Q_ENABLE"
))
->
rawValue
().
toBool
())
{
available
|=
TakeoffVehicleCapability
;
}
}
else
if
(
vehicle
->
fixedWing
()
||
vehicle
->
vtol
())
{
// Due to the way ArduPilot marks a vtol aircraft, we don't know if something is a vtol at initial connection.
// So we always enabled takeoff for fixed wing.
available
|=
TakeoffVehicleCapability
;
}
return
(
capabilities
&
available
)
==
capabilities
;
...
...
@@ -908,6 +906,11 @@ void APMFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle)
bool
APMFirmwarePlugin
::
_guidedModeTakeoff
(
Vehicle
*
vehicle
)
{
if
(
!
vehicle
->
multiRotor
()
&&
!
vehicle
->
vtol
())
{
qgcApp
()
->
showMessage
(
tr
(
"Vehicle does not support guided takeoff"
));
return
false
;
}
QString
takeoffAltParam
(
vehicle
->
vtol
()
?
QStringLiteral
(
"Q_RTL_ALT"
)
:
QStringLiteral
(
"PILOT_TKOFF_ALT"
));
float
paramDivisor
=
vehicle
->
vtol
()
?
1.0
:
100.0
;
// PILOT_TAKEOFF_ALT is in centimeters
...
...
@@ -965,6 +968,8 @@ void APMFirmwarePlugin::startMission(Vehicle* vehicle)
qgcApp
()
->
showMessage
(
QStringLiteral
(
"Unable to start mission. Vehicle takeoff failed."
));
return
;
}
}
else
{
return
;
}
}
...
...
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