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
03d8cf59
Unverified
Commit
03d8cf59
authored
Jul 15, 2018
by
Don Gagne
Committed by
GitHub
Jul 15, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6719 from DonLakeFlyer/ArduPilotMissionFix
Carryover ArduPilot changes from stable
parents
e3833aa5
438cf74c
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
9 additions
and
1 deletion
+9
-1
PlanManager.cc
src/MissionManager/PlanManager.cc
+8
-0
PlanManager.h
src/MissionManager/PlanManager.h
+1
-1
No files found.
src/MissionManager/PlanManager.cc
View file @
03d8cf59
...
...
@@ -589,6 +589,14 @@ void PlanManager::_handleMissionAck(const mavlink_message_t& message)
return
;
}
if
(
_vehicle
->
apmFirmware
()
&&
missionAck
.
type
==
MAV_MISSION_INVALID_SEQUENCE
)
{
// ArduPilot sends these Acks which can happen just due to noisy links causing duplicated requests being responded to.
// As far as I'm concerned this is incorrect protocol implementation but we need to deal with it anyway. So we just
// ignore it and if things really go haywire the timeouts will fire to fail the overall transaction.
qCDebug
(
PlanManagerLog
)
<<
QStringLiteral
(
"_handleMissionAck ArduPilot sending possibly bogus MAV_MISSION_INVALID_SEQUENCE"
).
arg
(
_planTypeString
())
<<
_planType
;
return
;
}
// Save the retry ack before calling _checkForExpectedAck since we'll need it to determine what
// type of a protocol sequence we are in.
AckType_t
savedExpectedAck
=
_expectedAck
;
...
...
src/MissionManager/PlanManager.h
View file @
03d8cf59
...
...
@@ -71,7 +71,7 @@ public:
// These values are public so the unit test can set appropriate signal wait times
// When passively waiting for a mission process, use a longer timeout.
static
const
int
_ackTimeoutMilliseconds
=
1
0
00
;
static
const
int
_ackTimeoutMilliseconds
=
1
5
00
;
// When actively retrying to request mission items, use a shorter timeout instead.
static
const
int
_retryTimeoutMilliseconds
=
250
;
static
const
int
_maxRetryCount
=
5
;
...
...
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