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
d19c22b7
Commit
d19c22b7
authored
Apr 09, 2017
by
Luis Vale Gonçalves
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Revised changes to ArduCopter Flight Modes
parent
002861d3
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
18 additions
and
12 deletions
+18
-12
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+10
-6
ArduCopterFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
+8
-6
No files found.
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
d19c22b7
...
...
@@ -25,21 +25,22 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
QMap
<
uint32_t
,
QString
>
enumToString
;
enumToString
.
insert
(
STABILIZE
,
"Stabilize"
);
enumToString
.
insert
(
ACRO
,
"Acro"
);
enumToString
.
insert
(
ALT_HOLD
,
"Alt Hold"
);
enumToString
.
insert
(
ALT_HOLD
,
"Alt
itude
Hold"
);
enumToString
.
insert
(
AUTO
,
"Auto"
);
enumToString
.
insert
(
GUIDED
,
"Guided"
);
enumToString
.
insert
(
LOITER
,
"Loiter"
);
enumToString
.
insert
(
RTL
,
"RTL"
);
enumToString
.
insert
(
CIRCLE
,
"Circle"
);
enumToString
.
insert
(
POSITION
,
"Position"
);
enumToString
.
insert
(
LAND
,
"Land"
);
enumToString
.
insert
(
OF_LOITER
,
"OF Loiter"
);
enumToString
.
insert
(
DRIFT
,
"Drift"
);
enumToString
.
insert
(
SPORT
,
"Sport"
);
enumToString
.
insert
(
FLIP
,
"Flip"
);
enumToString
.
insert
(
AUTOTUNE
,
"Autotune"
);
enumToString
.
insert
(
POS_HOLD
,
"Pos Hold"
);
enumToString
.
insert
(
POS_HOLD
,
"Pos
ition
Hold"
);
enumToString
.
insert
(
BRAKE
,
"Brake"
);
enumToString
.
insert
(
THROW
,
"Throw"
);
enumToString
.
insert
(
AVOID_ADSB
,
"Avoid ADSB"
);
enumToString
.
insert
(
GUIDED_NOGPS
,
"Guided No GPS"
);
setEnumToStringMapping
(
enumToString
);
}
...
...
@@ -55,15 +56,18 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
LOITER
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
RTL
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
CIRCLE
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
POSITION
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
LAND
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
OF_LOITER
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
DRIFT
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
SPORT
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
FLIP
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
AUTOTUNE
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
POS_HOLD
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
BRAKE
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
THROW
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
AVOID_ADSB
,
true
);
supportedFlightModes
<<
APMCopterMode
(
APMCopterMode
::
GUIDED_NOGPS
,
true
);
setSupportedModes
(
supportedFlightModes
);
if
(
!
_remapParamNameIntialized
)
{
...
...
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
View file @
d19c22b7
...
...
@@ -28,19 +28,21 @@ public:
LOITER
=
5
,
// Hold a single location
RTL
=
6
,
// AUTO control
CIRCLE
=
7
,
// AUTO control
POSITION
=
8
,
//
AUTO control
POSITION
=
8
,
//
Deprecated
LAND
=
9
,
// AUTO control
OF_LOITER
=
10
,
// Hold a single location using optical flow
// sensor
OF_LOITER
=
10
,
// Deprecated
DRIFT
=
11
,
// Drift 'Car Like' mode
RESERVED_12
=
12
,
// RESERVED FOR FUTURE USE
SPORT
=
13
,
// [TODO] Verify this is correct.
SPORT
=
13
,
FLIP
=
14
,
AUTOTUNE
=
15
,
POS_HOLD
=
16
,
// HYBRID LOITER.
BRAKE
=
17
BRAKE
=
17
,
THROW
=
18
,
AVOID_ADSB
=
19
,
GUIDED_NOGPS
=
20
,
};
static
const
int
modeCount
=
18
;
static
const
int
modeCount
=
21
;
APMCopterMode
(
uint32_t
mode
,
bool
settable
);
};
...
...
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