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
356369eb
Commit
356369eb
authored
Nov 06, 2014
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #963 from DonLakeFlyer/RC_CHANNELS_RAW
Disregard RC_CHANNELS_RAW for signals
parents
4356914d
7a119bc4
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
2 additions
and
29 deletions
+2
-29
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+2
-3
UAS.cc
src/uas/UAS.cc
+0
-26
No files found.
src/comm/MAVLinkSimulationLink.cc
View file @
356369eb
...
...
@@ -438,9 +438,8 @@ void MAVLinkSimulationLink::mainloop()
static
int
rcCounter
=
0
;
if
(
rcCounter
==
2
)
{
mavlink_rc_channels_
raw_
t
chan
;
mavlink_rc_channels_t
chan
;
chan
.
time_boot_ms
=
0
;
chan
.
port
=
0
;
chan
.
chan1_raw
=
1000
+
((
int
)(
fabs
(
x
)
*
1000
)
%
2000
);
chan
.
chan2_raw
=
1000
+
((
int
)(
fabs
(
y
)
*
1000
)
%
2000
);
chan
.
chan3_raw
=
1000
+
((
int
)(
fabs
(
z
)
*
1000
)
%
2000
);
...
...
@@ -450,7 +449,7 @@ void MAVLinkSimulationLink::mainloop()
chan
.
chan7_raw
=
(
chan
.
chan4_raw
+
chan
.
chan2_raw
)
/
2.0
f
;
chan
.
chan8_raw
=
0
;
chan
.
rssi
=
100
;
mavlink_msg_rc_channels_
raw_
encode
(
systemId
,
componentId
,
&
msg
,
&
chan
);
mavlink_msg_rc_channels_encode
(
systemId
,
componentId
,
&
msg
,
&
chan
);
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
...
...
src/uas/UAS.cc
View file @
356369eb
...
...
@@ -956,32 +956,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
homePositionChanged
(
uasId
,
pos
.
latitude
/
10000000.0
,
pos
.
longitude
/
10000000.0
,
pos
.
altitude
/
1000.0
);
}
break
;
case
MAVLINK_MSG_ID_RC_CHANNELS_RAW
:
{
mavlink_rc_channels_raw_t
channels
;
mavlink_msg_rc_channels_raw_decode
(
&
message
,
&
channels
);
const
unsigned
int
portWidth
=
8
;
// XXX magic number
emit
remoteControlRSSIChanged
(
channels
.
rssi
/
255.0
f
);
if
(
channels
.
chan1_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
0
,
channels
.
chan1_raw
);
if
(
channels
.
chan2_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
1
,
channels
.
chan2_raw
);
if
(
channels
.
chan3_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
2
,
channels
.
chan3_raw
);
if
(
channels
.
chan4_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
3
,
channels
.
chan4_raw
);
if
(
channels
.
chan5_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
4
,
channels
.
chan5_raw
);
if
(
channels
.
chan6_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
5
,
channels
.
chan6_raw
);
if
(
channels
.
chan7_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
6
,
channels
.
chan7_raw
);
if
(
channels
.
chan8_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
7
,
channels
.
chan8_raw
);
}
break
;
case
MAVLINK_MSG_ID_RC_CHANNELS
:
{
mavlink_rc_channels_t
channels
;
...
...
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