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
265eac97
Commit
265eac97
authored
May 22, 2014
by
Bryant Mairs
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Output clearer errors to the user if the UAS reports an error when sending missions.
Also these messages are now all translated.
parent
e63127ad
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
31 additions
and
6 deletions
+31
-6
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+31
-6
No files found.
src/uas/UASWaypointManager.cc
View file @
265eac97
...
...
@@ -227,12 +227,37 @@ void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavli
emit
updateStatusString
(
"done."
);
}
else
if
((
current_state
==
WP_SENDLIST
||
current_state
==
WP_SENDLIST_SENDWPS
)
&&
wpa
->
type
!=
0
)
{
//give up transmitting if a WP is rejected
if
(
wpa
->
type
==
1
)
{
emit
updateStatusString
(
"upload failed: general error"
);
}
else
if
(
wpa
->
type
==
2
)
{
emit
updateStatusString
(
"upload failed: coordinate frame unsupported."
);
}
else
{
emit
updateStatusString
(
"upload failed: other error."
);
switch
(
wpa
->
type
)
{
case
MAV_MISSION_UNSUPPORTED_FRAME
:
emit
updateStatusString
(
tr
(
"ERROR: Coordinate frame unsupported."
));
break
;
case
MAV_MISSION_UNSUPPORTED
:
emit
updateStatusString
(
tr
(
"ERROR: Unsupported command."
));
break
;
case
MAV_MISSION_NO_SPACE
:
emit
updateStatusString
(
tr
(
"ERROR: Mission count exceeds storage."
));
break
;
case
MAV_MISSION_INVALID
:
case
MAV_MISSION_INVALID_PARAM1
:
case
MAV_MISSION_INVALID_PARAM2
:
case
MAV_MISSION_INVALID_PARAM3
:
case
MAV_MISSION_INVALID_PARAM4
:
case
MAV_MISSION_INVALID_PARAM5_X
:
case
MAV_MISSION_INVALID_PARAM6_Y
:
case
MAV_MISSION_INVALID_PARAM7
:
emit
updateStatusString
(
tr
(
"ERROR: A specified parameter was invalid."
));
break
;
case
MAV_MISSION_INVALID_SEQUENCE
:
emit
updateStatusString
(
tr
(
"ERROR: Mission received out of sequence."
));
break
;
case
MAV_MISSION_DENIED
:
emit
updateStatusString
(
tr
(
"ERROR: UAS not accepting missions."
));
break
;
case
MAV_MISSION_ERROR
:
default:
emit
updateStatusString
(
tr
(
"ERROR: Unspecified error"
));
break
;
}
protocol_timer
.
stop
();
current_state
=
WP_IDLE
;
...
...
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