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
6422cc92
Commit
6422cc92
authored
Jul 30, 2019
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
parent
18bd5177
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
48 additions
and
40 deletions
+48
-40
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+44
-38
ArduCopterFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
+4
-2
No files found.
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
6422cc92
...
...
@@ -23,50 +23,56 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
APMCustomMode
(
mode
,
settable
)
{
setEnumToStringMapping
({
{
STABILIZE
,
"Stabilize"
},
{
ACRO
,
"Acro"
},
{
ALT_HOLD
,
"Altitude Hold"
},
{
AUTO
,
"Auto"
},
{
GUIDED
,
"Guided"
},
{
LOITER
,
"Loiter"
},
{
RTL
,
"RTL"
},
{
CIRCLE
,
"Circle"
},
{
LAND
,
"Land"
},
{
DRIFT
,
"Drift"
},
{
SPORT
,
"Sport"
},
{
FLIP
,
"Flip"
},
{
AUTOTUNE
,
"Autotune"
},
{
POS_HOLD
,
"Position Hold"
},
{
BRAKE
,
"Brake"
},
{
THROW
,
"Throw"
},
{
AVOID_ADSB
,
"Avoid ADSB"
},
{
GUIDED_NOGPS
,
"Guided No GPS"
},
{
SAFE_RTL
,
"Smart RTL"
},
{
STABILIZE
,
"Stabilize"
},
{
ACRO
,
"Acro"
},
{
ALT_HOLD
,
"Altitude Hold"
},
{
AUTO
,
"Auto"
},
{
GUIDED
,
"Guided"
},
{
LOITER
,
"Loiter"
},
{
RTL
,
"RTL"
},
{
CIRCLE
,
"Circle"
},
{
LAND
,
"Land"
},
{
DRIFT
,
"Drift"
},
{
SPORT
,
"Sport"
},
{
FLIP
,
"Flip"
},
{
AUTOTUNE
,
"Autotune"
},
{
POS_HOLD
,
"Position Hold"
},
{
BRAKE
,
"Brake"
},
{
THROW
,
"Throw"
},
{
AVOID_ADSB
,
"Avoid ADSB"
},
{
GUIDED_NOGPS
,
"Guided No GPS"
},
{
SMART_RTL
,
"Smart RTL"
},
{
FLOWHOLD
,
"Flow Hold"
},
{
FOLLOW
,
"Follow"
},
{
ZIGZAG
,
"ZigZag"
},
});
}
ArduCopterFirmwarePlugin
::
ArduCopterFirmwarePlugin
(
void
)
{
setSupportedModes
({
APMCopterMode
(
APMCopterMode
::
STABILIZE
,
true
),
APMCopterMode
(
APMCopterMode
::
ACRO
,
true
),
APMCopterMode
(
APMCopterMode
::
ALT_HOLD
,
true
),
APMCopterMode
(
APMCopterMode
::
AUTO
,
true
),
APMCopterMode
(
APMCopterMode
::
GUIDED
,
true
),
APMCopterMode
(
APMCopterMode
::
LOITER
,
true
),
APMCopterMode
(
APMCopterMode
::
RTL
,
true
),
APMCopterMode
(
APMCopterMode
::
CIRCLE
,
true
),
APMCopterMode
(
APMCopterMode
::
LAND
,
true
),
APMCopterMode
(
APMCopterMode
::
DRIFT
,
true
),
APMCopterMode
(
APMCopterMode
::
SPORT
,
true
),
APMCopterMode
(
APMCopterMode
::
FLIP
,
true
),
APMCopterMode
(
APMCopterMode
::
AUTOTUNE
,
true
),
APMCopterMode
(
APMCopterMode
::
POS_HOLD
,
true
),
APMCopterMode
(
APMCopterMode
::
BRAKE
,
true
),
APMCopterMode
(
APMCopterMode
::
THROW
,
true
),
APMCopterMode
(
APMCopterMode
::
AVOID_ADSB
,
true
),
APMCopterMode
(
APMCopterMode
::
GUIDED_NOGPS
,
true
),
APMCopterMode
(
APMCopterMode
::
SAFE_RTL
,
true
),
APMCopterMode
(
APMCopterMode
::
STABILIZE
,
true
),
APMCopterMode
(
APMCopterMode
::
ACRO
,
true
),
APMCopterMode
(
APMCopterMode
::
ALT_HOLD
,
true
),
APMCopterMode
(
APMCopterMode
::
AUTO
,
true
),
APMCopterMode
(
APMCopterMode
::
GUIDED
,
true
),
APMCopterMode
(
APMCopterMode
::
LOITER
,
true
),
APMCopterMode
(
APMCopterMode
::
RTL
,
true
),
APMCopterMode
(
APMCopterMode
::
CIRCLE
,
true
),
APMCopterMode
(
APMCopterMode
::
LAND
,
true
),
APMCopterMode
(
APMCopterMode
::
DRIFT
,
true
),
APMCopterMode
(
APMCopterMode
::
SPORT
,
true
),
APMCopterMode
(
APMCopterMode
::
FLIP
,
true
),
APMCopterMode
(
APMCopterMode
::
AUTOTUNE
,
true
),
APMCopterMode
(
APMCopterMode
::
POS_HOLD
,
true
),
APMCopterMode
(
APMCopterMode
::
BRAKE
,
true
),
APMCopterMode
(
APMCopterMode
::
THROW
,
true
),
APMCopterMode
(
APMCopterMode
::
AVOID_ADSB
,
true
),
APMCopterMode
(
APMCopterMode
::
GUIDED_NOGPS
,
true
),
APMCopterMode
(
APMCopterMode
::
SMART_RTL
,
true
),
APMCopterMode
(
APMCopterMode
::
FLOWHOLD
,
true
),
APMCopterMode
(
APMCopterMode
::
FOLLOW
,
true
),
APMCopterMode
(
APMCopterMode
::
ZIGZAG
,
true
),
});
if
(
!
_remapParamNameIntialized
)
{
...
...
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
View file @
6422cc92
...
...
@@ -41,9 +41,11 @@ public:
THROW
=
18
,
AVOID_ADSB
=
19
,
GUIDED_NOGPS
=
20
,
SAFE_RTL
=
21
,
//Safe Return to Launch
SMART_RTL
=
21
,
// SMART_RTL returns to home by retracing its steps
FLOWHOLD
=
22
,
// FLOWHOLD holds position with optical flow without rangefinder
FOLLOW
=
23
,
// follow attempts to follow another vehicle or ground station
ZIGZAG
=
24
,
// ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B
};
static
const
int
modeCount
=
22
;
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