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
367e276c
Unverified
Commit
367e276c
authored
Aug 13, 2019
by
Don Gagne
Committed by
GitHub
Aug 13, 2019
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #7646 from DonLakeFlyer/ArduCopterFlightModes
ArduCopter: Add Follow, Flow Hold, ZigZag flight modes
parents
f6e72014
da28a454
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
49 additions
and
44 deletions
+49
-44
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+44
-38
ArduCopterFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
+4
-2
ArduPlaneFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h
+0
-1
ArduRoverFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h
+0
-1
ArduSubFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h
+0
-1
Vehicle.cc
src/Vehicle/Vehicle.cc
+1
-1
No files found.
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
367e276c
...
...
@@ -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 Vehicle"
},
{
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 @
367e276c
...
...
@@ -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
);
};
...
...
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h
View file @
367e276c
...
...
@@ -42,7 +42,6 @@ public:
QLOITER
=
19
,
QLAND
=
20
,
QRTL
=
21
,
modeCount
};
APMPlaneMode
(
uint32_t
mode
,
bool
settable
);
...
...
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h
View file @
367e276c
...
...
@@ -33,7 +33,6 @@ public:
GUIDED
=
15
,
INITIALIZING
=
16
,
};
static
const
int
modeCount
=
17
;
APMRoverMode
(
uint32_t
mode
,
bool
settable
);
};
...
...
src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h
View file @
367e276c
...
...
@@ -96,7 +96,6 @@ public:
RESERVED_18
=
18
,
MANUAL
=
19
};
static
const
int
modeCount
=
20
;
APMSubMode
(
uint32_t
mode
,
bool
settable
);
};
...
...
src/Vehicle/Vehicle.cc
View file @
367e276c
...
...
@@ -3041,7 +3041,7 @@ void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord)
if
(
!
coordinate
().
isValid
())
{
return
;
}
double
maxDistance
=
1000.0
;
double
maxDistance
=
1000
0
.0
;
if
(
coordinate
().
distanceTo
(
gotoCoord
)
>
maxDistance
)
{
qgcApp
()
->
showMessage
(
QString
(
"New location is too far. Must be less than %1 %2"
).
arg
(
qRound
(
FactMetaData
::
metersToAppSettingsDistanceUnits
(
maxDistance
).
toDouble
())).
arg
(
FactMetaData
::
appSettingsDistanceUnitsString
()));
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