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
57cdf65b
Commit
57cdf65b
authored
Nov 22, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Add supportedMissionCommands
parent
c8942215
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
31 additions
and
0 deletions
+31
-0
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+10
-0
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+1
-0
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+3
-0
GenericFirmwarePlugin.cc
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc
+6
-0
GenericFirmwarePlugin.h
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h
+1
-0
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+9
-0
PX4FirmwarePlugin.h
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
+1
-0
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
57cdf65b
...
...
@@ -389,3 +389,13 @@ void APMFirmwarePlugin::addMetaDataToFact(Fact* fact)
{
_parameterMetaData
.
addMetaDataToFact
(
fact
);
}
QList
<
MAV_CMD
>
APMFirmwarePlugin
::
supportedMissionCommands
(
void
)
{
QList
<
MAV_CMD
>
list
;
// FIXME: Temp list, just dup of PX4
list
<<
MAV_CMD_NAV_WAYPOINT
<<
MAV_CMD_NAV_LOITER_UNLIM
<<
MAV_CMD_NAV_LOITER_TURNS
<<
MAV_CMD_NAV_LOITER_TIME
<<
MAV_CMD_NAV_RETURN_TO_LAUNCH
<<
MAV_CMD_NAV_LAND
<<
MAV_CMD_NAV_TAKEOFF
<<
MAV_CMD_CONDITION_DELAY
<<
MAV_CMD_DO_JUMP
;
return
list
;
}
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
57cdf65b
...
...
@@ -91,6 +91,7 @@ public:
virtual
bool
sendHomePositionToVehicle
(
void
);
virtual
void
addMetaDataToFact
(
Fact
*
fact
);
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
(
"SYSID_SW_TYPE"
);
}
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
protected:
/// All access to singleton is through stack specific implementation
...
...
src/FirmwarePlugin/FirmwarePlugin.h
View file @
57cdf65b
...
...
@@ -109,6 +109,9 @@ public:
/// Adds the parameter meta data to the Fact
virtual
void
addMetaDataToFact
(
Fact
*
fact
)
=
0
;
/// List of supported mission commands. Empty list for all commands supported.
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
)
=
0
;
};
#endif
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc
View file @
57cdf65b
...
...
@@ -118,3 +118,9 @@ void GenericFirmwarePlugin::addMetaDataToFact(Fact* fact)
FactMetaData
*
metaData
=
new
FactMetaData
(
fact
->
type
(),
fact
);
fact
->
setMetaData
(
metaData
);
}
QList
<
MAV_CMD
>
GenericFirmwarePlugin
::
supportedMissionCommands
(
void
)
{
// Generic supports all commands
return
QList
<
MAV_CMD
>
();
}
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h
View file @
57cdf65b
...
...
@@ -47,6 +47,7 @@ public:
virtual
bool
sendHomePositionToVehicle
(
void
);
virtual
void
addMetaDataToFact
(
Fact
*
fact
);
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
();
}
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
};
#endif
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
57cdf65b
...
...
@@ -207,3 +207,12 @@ void PX4FirmwarePlugin::addMetaDataToFact(Fact* fact)
{
_parameterMetaData
.
addMetaDataToFact
(
fact
);
}
QList
<
MAV_CMD
>
PX4FirmwarePlugin
::
supportedMissionCommands
(
void
)
{
QList
<
MAV_CMD
>
list
;
list
<<
MAV_CMD_NAV_WAYPOINT
<<
MAV_CMD_NAV_LOITER_UNLIM
<<
MAV_CMD_NAV_LOITER_TURNS
<<
MAV_CMD_NAV_LOITER_TIME
<<
MAV_CMD_NAV_RETURN_TO_LAUNCH
<<
MAV_CMD_NAV_LAND
<<
MAV_CMD_NAV_TAKEOFF
<<
MAV_CMD_CONDITION_DELAY
<<
MAV_CMD_DO_JUMP
;
return
list
;
}
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
View file @
57cdf65b
...
...
@@ -47,6 +47,7 @@ public:
virtual
bool
sendHomePositionToVehicle
(
void
);
virtual
void
addMetaDataToFact
(
Fact
*
fact
);
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
(
"SYS_AUTOSTART"
);
}
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
private:
PX4ParameterMetaData
_parameterMetaData
;
...
...
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