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
d19ac386
Commit
d19ac386
authored
Sep 05, 2012
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Persistence and audio fixes increasing work convenience
parent
6ffe3d86
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
56 additions
and
14 deletions
+56
-14
SerialLink.cc
src/comm/SerialLink.cc
+4
-4
UAS.cc
src/uas/UAS.cc
+40
-5
UAS.h
src/uas/UAS.h
+3
-0
MAVLinkDecoder.cc
src/ui/MAVLinkDecoder.cc
+5
-5
SerialConfigurationWindow.cc
src/ui/SerialConfigurationWindow.cc
+4
-0
No files found.
src/comm/SerialLink.cc
View file @
d19ac386
...
...
@@ -363,7 +363,7 @@ void SerialLink::loadSettings()
settings
.
sync
();
if
(
settings
.
contains
(
"SERIALLINK_COMM_PORT"
))
{
if
(
porthandle
==
""
)
setPortName
(
settings
.
value
(
"SERIALLINK_COMM_PORT"
).
toString
());
setPortName
(
settings
.
value
(
"SERIALLINK_COMM_PORT"
).
toString
());
setBaudRateType
(
settings
.
value
(
"SERIALLINK_COMM_BAUD"
).
toInt
());
setParityType
(
settings
.
value
(
"SERIALLINK_COMM_PARITY"
).
toInt
());
setStopBits
(
settings
.
value
(
"SERIALLINK_COMM_STOPBITS"
).
toInt
());
...
...
@@ -376,7 +376,7 @@ void SerialLink::writeSettings()
{
// Store settings
QSettings
settings
(
QGC
::
COMPANYNAME
,
QGC
::
APPNAME
);
settings
.
setValue
(
"SERIALLINK_COMM_PORT"
,
this
->
porthandle
);
settings
.
setValue
(
"SERIALLINK_COMM_PORT"
,
getPortName
()
);
settings
.
setValue
(
"SERIALLINK_COMM_BAUD"
,
getBaudRateType
());
settings
.
setValue
(
"SERIALLINK_COMM_PARITY"
,
getParityType
());
settings
.
setValue
(
"SERIALLINK_COMM_STOPBITS"
,
getStopBits
());
...
...
@@ -925,13 +925,13 @@ bool SerialLink::setBaudRateType(int rateIndex)
// These minimum and maximum baud rates were based on those enumerated in qportsettings.h.
#if defined(Q_OS_WIN32) || defined(Q_OS_WINCE)
const
int
minBaud
=
(
int
)
QPortSettings
::
BAUDR_110
;
const
int
maxBaud
=
(
int
)
QPortSettings
::
BAUDR_
2560
00
;
const
int
maxBaud
=
(
int
)
QPortSettings
::
BAUDR_
9216
00
;
#elif defined(Q_OS_LINUX)
const
int
minBaud
=
(
int
)
QPortSettings
::
BAUDR_50
;
const
int
maxBaud
=
(
int
)
QPortSettings
::
BAUDR_921600
;
#elif defined(Q_OS_UNIX) || defined(Q_OS_DARWIN)
const
int
minBaud
=
(
int
)
QPortSettings
::
BAUDR_50
;
const
int
maxBaud
=
(
int
)
QPortSettings
::
BAUDR_
1152
00
;
const
int
maxBaud
=
(
int
)
QPortSettings
::
BAUDR_
9216
00
;
#endif
if
(
rateIndex
>=
minBaud
&&
rateIndex
<=
maxBaud
)
...
...
src/uas/UAS.cc
View file @
d19ac386
...
...
@@ -102,7 +102,9 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
isGlobalPositionKnown
(
false
),
systemIsArmed
(
false
),
nedPosGlobalOffset
(
0
,
0
,
0
),
nedAttGlobalOffset
(
0
,
0
,
0
)
nedAttGlobalOffset
(
0
,
0
,
0
),
connectionLost
(
false
),
lastVoltageWarning
(
0
)
{
for
(
unsigned
int
i
=
0
;
i
<
255
;
++
i
)
...
...
@@ -197,10 +199,23 @@ void UAS::updateState()
{
// Check if heartbeat timed out
quint64
heartbeatInterval
=
QGC
::
groundTimeUsecs
()
-
lastHeartbeat
;
if
(
heartbeatInterval
>
timeoutIntervalHeartbeat
)
if
(
!
connectionLost
&&
(
heartbeatInterval
>
timeoutIntervalHeartbeat
)
)
{
emit
heartbeatTimeout
(
heartbeatInterval
);
emit
heartbeatTimeout
();
connectionLost
=
true
;
connectionLossTime
=
heartbeatInterval
;
QString
audiostring
=
QString
(
"Link lost to system %1"
).
arg
(
this
->
getUASID
());
GAudioOutput
::
instance
()
->
say
(
audiostring
.
toLower
());
}
// Connection gained
if
(
connectionLost
&&
(
heartbeatInterval
<
timeoutIntervalHeartbeat
))
{
QString
audiostring
=
QString
(
"Link regained to system %1 after %2 seconds"
).
arg
(
this
->
getUASID
()).
arg
((
int
)(
connectionLossTime
/
1000000
));
GAudioOutput
::
instance
()
->
say
(
audiostring
.
toLower
());
connectionLost
=
false
;
connectionLossTime
=
0
;
}
// Position lock is set by the MAVLink message handler
...
...
@@ -406,7 +421,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
shortStateText
=
uasState
;
stateAudio
=
tr
(
" changed status to "
)
+
uasState
;
// Adjust for better audio
if
(
uasState
==
QString
(
"STANDBY"
))
uasState
=
QString
(
"standing by"
);
if
(
uasState
==
QString
(
"EMERGENCY"
))
uasState
=
QString
(
"emergency condition"
);
if
(
uasState
==
QString
(
"CRITICAL"
))
uasState
=
QString
(
"critical condition"
);
if
(
uasState
==
QString
(
"SHUTDOWN"
))
uasState
=
QString
(
"shutting down"
);
stateAudio
=
uasState
;
}
if
(
this
->
mode
!=
static_cast
<
int
>
(
state
.
base_mode
))
...
...
@@ -480,6 +501,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
lpVoltage
=
filterVoltage
(
currentVoltage
);
tickLowpassVoltage
=
tickLowpassVoltage
*
0.8
f
+
0.2
f
*
currentVoltage
;
// We don't want to tick above the threshold
if
(
tickLowpassVoltage
>
tickVoltage
)
{
...
...
@@ -487,9 +509,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
if
((
startVoltage
>
0.0
f
)
&&
(
tickLowpassVoltage
<
tickVoltage
)
&&
(
fabs
(
lastTickVoltageValue
-
tickLowpassVoltage
)
>
0.1
f
)
&&
(
lpVoltage
<
tickVoltage
))
/* warn if lower than treshold */
&&
(
lpVoltage
<
tickVoltage
)
/* warn only if we have at least the voltage of an empty LiPo cell, else we're sampling something wrong */
&&
(
currentVoltage
>
3.3
f
)
/* warn only if current voltage is really still lower by a reasonable amount */
&&
((
currentVoltage
-
0.1
f
)
<
tickVoltage
)
/* warn only every 12 seconds */
&&
(
QGC
::
groundTimeUsecs
()
-
lastVoltageWarning
)
>
12000000
)
{
GAudioOutput
::
instance
()
->
say
(
QString
(
"voltage warning: %1 volt"
).
arg
(
lpVoltage
,
0
,
'f'
,
1
,
QChar
(
' '
)));
GAudioOutput
::
instance
()
->
say
(
QString
(
"voltage warning: %1 volts"
).
arg
(
lpVoltage
,
0
,
'f'
,
1
,
QChar
(
' '
)));
lastVoltageWarning
=
QGC
::
groundTimeUsecs
();
lastTickVoltageValue
=
tickLowpassVoltage
;
}
...
...
@@ -2641,6 +2671,11 @@ QString UAS::getAudioModeTextFor(int id)
{
mode
+=
"manual"
;
}
else
{
// Nothing else applies, we're in preflight
mode
+=
"preflight"
;
}
if
(
modeid
!=
0
)
{
...
...
src/uas/UAS.h
View file @
d19ac386
...
...
@@ -671,6 +671,9 @@ protected:
quint64
getUnixReferenceTime
(
quint64
time
);
int
componentID
[
256
];
bool
componentMulti
[
256
];
bool
connectionLost
;
///< Flag indicates a timed out connection
quint64
connectionLossTime
;
///< Time the connection was interrupted
quint64
lastVoltageWarning
;
///< Time at which the last voltage warning occured
protected
slots
:
/** @brief Write settings to disk */
...
...
src/ui/MAVLinkDecoder.cc
View file @
d19ac386
...
...
@@ -57,8 +57,8 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
{
mavlink_system_time_t
timebase
;
mavlink_msg_system_time_decode
(
&
message
,
&
timebase
);
onboardTimeOffset
[
message
.
sysid
]
=
timebase
.
time_unix_usec
/
1000
-
timebase
.
time_boot_ms
;
onboardToGCSUnixTimeOffsetAndDelay
[
message
.
sysid
]
=
static_cast
<
qint64
>
(
QGC
::
groundTimeMilliseconds
()
-
timebase
.
time_unix_usec
/
1000
);
onboardTimeOffset
[
message
.
sysid
]
=
(
timebase
.
time_unix_usec
+
500
)
/
1000
-
timebase
.
time_boot_ms
;
onboardToGCSUnixTimeOffsetAndDelay
[
message
.
sysid
]
=
static_cast
<
qint64
>
(
QGC
::
groundTimeMilliseconds
()
-
(
timebase
.
time_unix_usec
+
500
)
/
1000
);
}
else
{
...
...
@@ -77,7 +77,7 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
else
if
(
QString
(
messageInfo
[
msgid
].
fields
[
fieldid
].
name
).
contains
(
"usec"
)
&&
messageInfo
[
msgid
].
fields
[
fieldid
].
type
==
MAVLINK_TYPE_UINT64_T
)
{
time
=
*
((
quint64
*
)(
m
+
messageInfo
[
msgid
].
fields
[
fieldid
].
wire_offset
));
time
=
time
/
1000
;
// Scale to milliseconds
time
=
(
time
+
500
)
/
1000
;
// Scale to milliseconds, round up/down correctly
}
else
{
...
...
@@ -182,7 +182,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
mavlink_debug_vect_t
debug
;
mavlink_msg_debug_vect_decode
(
msg
,
&
debug
);
name
=
name
.
arg
(
QString
(
debug
.
name
),
fieldName
);
time
=
debug
.
time_usec
/
1000
;
time
=
(
debug
.
time_usec
+
500
)
/
1000
;
// Scale to milliseconds, round up/down correctly
}
else
if
(
msgid
==
MAVLINK_MSG_ID_DEBUG
)
{
...
...
@@ -195,7 +195,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
{
mavlink_named_value_float_t
debug
;
mavlink_msg_named_value_float_decode
(
msg
,
&
debug
);
name
=
name
.
arg
(
debug
.
name
).
arg
(
fieldName
)
;
name
=
debug
.
name
;
time
=
debug
.
time_boot_ms
;
}
else
if
(
msgid
==
MAVLINK_MSG_ID_NAMED_VALUE_INT
)
...
...
src/ui/SerialConfigurationWindow.cc
View file @
d19ac386
...
...
@@ -111,6 +111,10 @@ SerialConfigurationWindow::SerialConfigurationWindow(LinkInterface* link, QWidge
ui
.
baudRate
->
addItem
(
QString
::
number
(
supportedBaudRates
.
at
(
i
)),
supportedBaudRates
.
at
(
i
));
}
// Load current link config
ui
.
portName
->
setCurrentIndex
(
ui
.
baudRate
->
findText
(
QString
(
"%1"
).
arg
(
this
->
link
->
getPortName
())));
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"port name:"
<<
QString
(
"%1"
).
arg
(
this
->
link
->
getPortName
());
connect
(
action
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
configureCommunication
()));
// Make sure that a change in the link name will be reflected in the UI
...
...
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