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
48a3ea0d
Commit
48a3ea0d
authored
Apr 21, 2015
by
dogmaphobic
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Changed RC RSSI to follow original spec.
parent
3f0592d2
Changes
4
Show whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
4 additions
and
26 deletions
+4
-26
UAS.cc
src/uas/UAS.cc
+1
-23
MainToolBar.cc
src/ui/toolbar/MainToolBar.cc
+1
-1
MainToolBar.h
src/ui/toolbar/MainToolBar.h
+1
-1
MainToolBar.qml
src/ui/toolbar/MainToolBar.qml
+1
-1
No files found.
src/uas/UAS.cc
View file @
48a3ea0d
...
@@ -923,28 +923,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -923,28 +923,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_rc_channels_t
channels
;
mavlink_rc_channels_t
channels
;
mavlink_msg_rc_channels_decode
(
&
message
,
&
channels
);
mavlink_msg_rc_channels_decode
(
&
message
,
&
channels
);
/*
emit
remoteControlRSSIChanged
(
channels
.
rssi
);
* Full RSSI field: 0b 1 111 1111
* | | |
* | | ^ These four bits encode a total of
* | | 16 RSSI levels. 15 = full, 0 = no signal
* | |
* | ^ These three bits encode a total of 8
* | digital RC input types.
* | 0: PPM, 1: SBUS, 2: Spektrum, 3: ST24
* |
* ^ If bit is set, RSSI encodes type + RSSI
*/
// TODO: Because the code on the firmware side never sets rssi to 0 on loss of connection
// we get a minimum value of 1 (3.5dB). This is what it does to compute it:
// msg.rssi |= (rc.rssi <= 100) ? ((rc.rssi / 7) + 1) : 15;
// Therefore, I'm eliminating bit 0 as well.
int
tRssi
=
(
channels
.
rssi
&
0x0E
)
*
7
;
if
(
tRssi
>
100
)
{
tRssi
=
100
;
}
emit
remoteControlRSSIChanged
((
uint8_t
)
tRssi
);
if
(
channels
.
chan1_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
0
)
if
(
channels
.
chan1_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
0
)
emit
remoteControlChannelRawChanged
(
0
,
channels
.
chan1_raw
);
emit
remoteControlChannelRawChanged
(
0
,
channels
.
chan1_raw
);
...
@@ -994,7 +973,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -994,7 +973,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
const
unsigned
int
portWidth
=
8
;
// XXX magic number
const
unsigned
int
portWidth
=
8
;
// XXX magic number
// TODO: This makes an assumption the RSSI has been normalized to 0-100
emit
remoteControlRSSIChanged
(
channels
.
rssi
);
emit
remoteControlRSSIChanged
(
channels
.
rssi
);
if
(
static_cast
<
uint16_t
>
(
channels
.
chan1_scaled
)
!=
UINT16_MAX
)
if
(
static_cast
<
uint16_t
>
(
channels
.
chan1_scaled
)
!=
UINT16_MAX
)
emit
remoteControlChannelScaledChanged
(
channels
.
port
*
portWidth
+
0
,
channels
.
chan1_scaled
/
10000.0
f
);
emit
remoteControlChannelScaledChanged
(
channels
.
port
*
portWidth
+
0
,
channels
.
chan1_scaled
/
10000.0
f
);
...
...
src/ui/toolbar/MainToolBar.cc
View file @
48a3ea0d
...
@@ -377,7 +377,7 @@ void MainToolBar::_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned
...
@@ -377,7 +377,7 @@ void MainToolBar::_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned
}
}
}
}
void
MainToolBar
::
_remoteControlRSSIChanged
(
floa
t
rssi
)
void
MainToolBar
::
_remoteControlRSSIChanged
(
uint8_
t
rssi
)
{
{
// We only care if we haveone single connection
// We only care if we haveone single connection
if
(
_connectionCount
==
1
)
{
if
(
_connectionCount
==
1
)
{
...
...
src/ui/toolbar/MainToolBar.h
View file @
48a3ea0d
...
@@ -159,7 +159,7 @@ private slots:
...
@@ -159,7 +159,7 @@ private slots:
void
_leaveMessageView
();
void
_leaveMessageView
();
void
_setSatLoc
(
UASInterface
*
uas
,
int
fix
);
void
_setSatLoc
(
UASInterface
*
uas
,
int
fix
);
void
_setProgressBarValue
(
float
value
);
void
_setProgressBarValue
(
float
value
);
void
_remoteControlRSSIChanged
(
floa
t
rssi
);
void
_remoteControlRSSIChanged
(
uint8_
t
rssi
);
void
_telemetryChanged
(
LinkInterface
*
link
,
unsigned
rxerrors
,
unsigned
fixed
,
unsigned
rssi
,
unsigned
remrssi
,
unsigned
txbuf
,
unsigned
noise
,
unsigned
remnoise
);
void
_telemetryChanged
(
LinkInterface
*
link
,
unsigned
rxerrors
,
unsigned
fixed
,
unsigned
rssi
,
unsigned
remrssi
,
unsigned
txbuf
,
unsigned
noise
,
unsigned
remnoise
);
private:
private:
...
...
src/ui/toolbar/MainToolBar.qml
View file @
48a3ea0d
...
@@ -351,7 +351,7 @@ Rectangle {
...
@@ -351,7 +351,7 @@ Rectangle {
id
:
rssiRC
id
:
rssiRC
width
:
getProportionalDimmension
(
55
)
width
:
getProportionalDimmension
(
55
)
height
:
cellHeight
height
:
cellHeight
visible
:
showMavStatus
()
&&
mainToolBar
.
showRSSI
visible
:
showMavStatus
()
&&
mainToolBar
.
showRSSI
&&
mainToolBar
.
remoteRSSI
<=
100
anchors.verticalCenter
:
parent
.
verticalCenter
anchors.verticalCenter
:
parent
.
verticalCenter
color
:
getRSSIColor
(
mainToolBar
.
remoteRSSI
);
color
:
getRSSIColor
(
mainToolBar
.
remoteRSSI
);
border.color
:
"
#00000000
"
border.color
:
"
#00000000
"
...
...
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