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
2e4ac6be
Commit
2e4ac6be
authored
Jun 23, 2014
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Add RC channel handling
parent
8f30c8be
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
52 additions
and
3 deletions
+52
-3
UAS.cc
src/uas/UAS.cc
+52
-3
No files found.
src/uas/UAS.cc
View file @
2e4ac6be
...
@@ -1003,6 +1003,55 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -1003,6 +1003,55 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
6
,
channels
.
chan7_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
6
,
channels
.
chan7_raw
);
if
(
channels
.
chan8_raw
!=
UINT16_MAX
)
if
(
channels
.
chan8_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
7
,
channels
.
chan8_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
7
,
channels
.
chan8_raw
);
}
break
;
case
MAVLINK_MSG_ID_RC_CHANNELS
:
{
mavlink_rc_channels_t
channels
;
mavlink_msg_rc_channels_decode
(
&
message
,
&
channels
);
// UINT8_MAX indicates this value is unknown
if
(
channels
.
rssi
!=
UINT8_MAX
)
{
emit
remoteControlRSSIChanged
(
channels
.
rssi
/
100.0
f
);
}
if
(
channels
.
chan1_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
0
)
emit
remoteControlChannelRawChanged
(
0
,
channels
.
chan1_raw
);
if
(
channels
.
chan2_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
1
)
emit
remoteControlChannelRawChanged
(
1
,
channels
.
chan2_raw
);
if
(
channels
.
chan3_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
2
)
emit
remoteControlChannelRawChanged
(
2
,
channels
.
chan3_raw
);
if
(
channels
.
chan4_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
3
)
emit
remoteControlChannelRawChanged
(
3
,
channels
.
chan4_raw
);
if
(
channels
.
chan5_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
4
)
emit
remoteControlChannelRawChanged
(
4
,
channels
.
chan5_raw
);
if
(
channels
.
chan6_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
5
)
emit
remoteControlChannelRawChanged
(
5
,
channels
.
chan6_raw
);
if
(
channels
.
chan7_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
6
)
emit
remoteControlChannelRawChanged
(
6
,
channels
.
chan7_raw
);
if
(
channels
.
chan8_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
7
)
emit
remoteControlChannelRawChanged
(
7
,
channels
.
chan8_raw
);
if
(
channels
.
chan9_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
8
)
emit
remoteControlChannelRawChanged
(
8
,
channels
.
chan9_raw
);
if
(
channels
.
chan10_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
9
)
emit
remoteControlChannelRawChanged
(
9
,
channels
.
chan10_raw
);
if
(
channels
.
chan11_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
10
)
emit
remoteControlChannelRawChanged
(
10
,
channels
.
chan11_raw
);
if
(
channels
.
chan12_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
11
)
emit
remoteControlChannelRawChanged
(
11
,
channels
.
chan12_raw
);
if
(
channels
.
chan13_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
12
)
emit
remoteControlChannelRawChanged
(
12
,
channels
.
chan13_raw
);
if
(
channels
.
chan14_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
13
)
emit
remoteControlChannelRawChanged
(
13
,
channels
.
chan14_raw
);
if
(
channels
.
chan15_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
14
)
emit
remoteControlChannelRawChanged
(
14
,
channels
.
chan15_raw
);
if
(
channels
.
chan16_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
15
)
emit
remoteControlChannelRawChanged
(
15
,
channels
.
chan16_raw
);
if
(
channels
.
chan17_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
16
)
emit
remoteControlChannelRawChanged
(
16
,
channels
.
chan17_raw
);
if
(
channels
.
chan18_raw
!=
UINT16_MAX
&&
channels
.
chancount
>
17
)
emit
remoteControlChannelRawChanged
(
17
,
channels
.
chan18_raw
);
}
}
break
;
break
;
case
MAVLINK_MSG_ID_RC_CHANNELS_SCALED
:
case
MAVLINK_MSG_ID_RC_CHANNELS_SCALED
:
...
@@ -1444,9 +1493,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -1444,9 +1493,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
break
;
break
;
#endif
#endif
// Messages to ignore
case
MAVLINK_MSG_ID_RAW_IMU
:
case
MAVLINK_MSG_ID_SCALED_IMU
:
case
MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT
:
case
MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT
:
{
{
//mavlink_set_local_position_setpoint_t p;
//mavlink_set_local_position_setpoint_t p;
...
@@ -1462,6 +1508,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -1462,6 +1508,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
navigationControllerErrorsChanged
(
this
,
p
.
alt_error
,
p
.
aspd_error
,
p
.
xtrack_error
);
emit
navigationControllerErrorsChanged
(
this
,
p
.
alt_error
,
p
.
aspd_error
,
p
.
xtrack_error
);
}
}
break
;
break
;
// Messages to ignore
case
MAVLINK_MSG_ID_RAW_IMU
:
case
MAVLINK_MSG_ID_SCALED_IMU
:
case
MAVLINK_MSG_ID_RAW_PRESSURE
:
case
MAVLINK_MSG_ID_RAW_PRESSURE
:
case
MAVLINK_MSG_ID_SCALED_PRESSURE
:
case
MAVLINK_MSG_ID_SCALED_PRESSURE
:
case
MAVLINK_MSG_ID_OPTICAL_FLOW
:
case
MAVLINK_MSG_ID_OPTICAL_FLOW
:
...
...
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