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
79b4c383
Commit
79b4c383
authored
Apr 01, 2018
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
ArduCopter Start Mission change
parent
94fbc660
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
6 additions
and
19 deletions
+6
-19
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+6
-19
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
79b4c383
...
...
@@ -990,26 +990,13 @@ void APMFirmwarePlugin::startMission(Vehicle* vehicle)
}
}
}
else
{
// Copter will not automatically start a mission from the ground so we have to command it to takeoff first
if
(
_guidedModeTakeoff
(
vehicle
,
qQNaN
()))
{
double
currentAlt
=
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
();
// Wait for vehicle to get off ground before switching to auto (10 seconds)
bool
didTakeoff
=
false
;
for
(
int
i
=
0
;
i
<
100
;
i
++
)
{
if
(
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
()
>=
currentAlt
+
1.0
)
{
didTakeoff
=
true
;
break
;
}
QGC
::
SLEEP
::
msleep
(
100
);
qgcApp
()
->
processEvents
(
QEventLoop
::
ExcludeUserInputEvents
);
}
if
(
!
didTakeoff
)
{
qgcApp
()
->
showMessage
(
tr
(
"Unable to start mission. Vehicle takeoff failed."
));
return
;
}
// Copter will automatically start a mission from the ground if you change to Auto and do a START+MIS
if
(
!
_setFlightModeAndValidate
(
vehicle
,
"Auto"
))
{
qgcApp
()
->
showMessage
(
tr
(
"Unable to start mission: Vehicle failed to change to Guided mode."
));
return
;
}
vehicle
->
sendMavCommand
(
vehicle
->
defaultComponentId
(),
MAV_CMD_MISSION_START
,
true
/*show error */
);
}
// Final step is to go into Auto
...
...
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