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
0313a43f
Commit
0313a43f
authored
Sep 28, 2018
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
parent
84dc0758
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
4 additions
and
2 deletions
+4
-2
Vehicle.cc
src/Vehicle/Vehicle.cc
+4
-2
No files found.
src/Vehicle/Vehicle.cc
View file @
0313a43f
...
...
@@ -825,9 +825,12 @@ void Vehicle::_handleStatusText(mavlink_message_t& message)
mavlink_msg_statustext_get_text
(
&
message
,
b
.
data
());
b
[
b
.
length
()
-
1
]
=
'\0'
;
QString
messageText
=
QString
(
b
);
int
severity
=
mavlink_msg_statustext_get_severity
(
&
message
);
bool
skipSpoken
=
false
;
if
(
messageText
.
startsWith
(
QStringLiteral
(
"PreArm"
))
||
messageText
.
startsWith
(
QStringLiteral
(
"preflight"
),
Qt
::
CaseInsensitive
))
{
bool
ardupilotPrearm
=
messageText
.
startsWith
(
QStringLiteral
(
"PreArm"
));
bool
px4Prearm
=
messageText
.
startsWith
(
QStringLiteral
(
"preflight"
),
Qt
::
CaseInsensitive
)
&&
severity
==
MAV_SEVERITY_CRITICAL
;
if
(
ardupilotPrearm
||
px4Prearm
)
{
// Limit repeated PreArm message to once every 10 seconds
if
(
_noisySpokenPrearmMap
.
contains
(
messageText
)
&&
_noisySpokenPrearmMap
[
messageText
].
msecsTo
(
QTime
::
currentTime
())
<
(
10
*
1000
))
{
skipSpoken
=
true
;
...
...
@@ -840,7 +843,6 @@ void Vehicle::_handleStatusText(mavlink_message_t& message)
// If the message is NOTIFY or higher severity, or starts with a '#',
// then read it aloud.
int
severity
=
mavlink_msg_statustext_get_severity
(
&
message
);
if
(
messageText
.
startsWith
(
"#"
)
||
severity
<=
MAV_SEVERITY_NOTICE
)
{
messageText
.
remove
(
"#"
);
if
(
!
skipSpoken
)
{
...
...
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