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
1432ebed
Commit
1432ebed
authored
Oct 20, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Assume VTOL type is coming from HEARTBEAT
parent
e4e1936d
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
1 addition
and
16 deletions
+1
-16
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+1
-15
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+0
-1
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
1432ebed
...
...
@@ -162,9 +162,7 @@ bool APMFirmwarePlugin::isCapable(const Vehicle* vehicle, FirmwareCapabilities c
uint32_t
available
=
SetFlightModeCapability
|
PauseVehicleCapability
|
GuidedModeCapability
;
if
(
vehicle
->
multiRotor
())
{
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.
}
else
if
(
vehicle
->
vtol
())
{
available
|=
TakeoffVehicleCapability
;
}
...
...
@@ -887,18 +885,6 @@ void APMFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
vehicle
->
sendMessageOnLink
(
vehicle
->
priorityLink
(),
msg
);
}
bool
APMFirmwarePlugin
::
isVtol
(
const
Vehicle
*
vehicle
)
const
{
if
(
vehicle
->
fixedWing
())
{
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"Q_ENABLE"
))
&&
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"Q_ENABLE"
))
->
rawValue
().
toBool
())
{
return
true
;
}
}
return
false
;
}
void
APMFirmwarePlugin
::
guidedModeTakeoff
(
Vehicle
*
vehicle
)
{
_guidedModeTakeoff
(
vehicle
);
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
1432ebed
...
...
@@ -74,7 +74,6 @@ public:
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
)
override
;
AutoPilotPlugin
*
autopilotPlugin
(
Vehicle
*
vehicle
)
override
;
bool
isVtol
(
const
Vehicle
*
vehicle
)
const
override
;
bool
isCapable
(
const
Vehicle
*
vehicle
,
FirmwareCapabilities
capabilities
)
override
;
void
setGuidedMode
(
Vehicle
*
vehicle
,
bool
guidedMode
)
override
;
void
guidedModeTakeoff
(
Vehicle
*
vehicle
)
override
;
...
...
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