Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
f2678c5c
Commit
f2678c5c
authored
Dec 29, 2013
by
Lorenz Meier
Browse files
Extended RC config to 18 channels, dealing with multi-port messages
parent
7524a806
Changes
5
Expand all
Hide whitespace changes
Inline
Side-by-side
src/uas/UAS.cc
View file @
f2678c5c
...
...
@@ -1002,14 +1002,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_rc_channels_raw_t
channels
;
mavlink_msg_rc_channels_raw_decode
(
&
message
,
&
channels
);
emit
remoteControlRSSIChanged
(
channels
.
rssi
/
255.0
f
);
emit
remoteControlChannelRawChanged
(
0
,
channels
.
chan1_raw
);
emit
remoteControlChannelRawChanged
(
1
,
channels
.
chan2_raw
);
emit
remoteControlChannelRawChanged
(
2
,
channels
.
chan3_raw
);
emit
remoteControlChannelRawChanged
(
3
,
channels
.
chan4_raw
);
emit
remoteControlChannelRawChanged
(
4
,
channels
.
chan5_raw
);
emit
remoteControlChannelRawChanged
(
5
,
channels
.
chan6_raw
);
emit
remoteControlChannelRawChanged
(
6
,
channels
.
chan7_raw
);
emit
remoteControlChannelRawChanged
(
7
,
channels
.
chan8_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
+
0
,
channels
.
chan1_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
+
1
,
channels
.
chan2_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
+
2
,
channels
.
chan3_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
+
3
,
channels
.
chan4_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
+
4
,
channels
.
chan5_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
+
5
,
channels
.
chan6_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
+
6
,
channels
.
chan7_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
+
7
,
channels
.
chan8_raw
);
}
break
;
case
MAVLINK_MSG_ID_RC_CHANNELS_SCALED
:
...
...
src/ui/MAVLinkDecoder.cc
View file @
f2678c5c
...
...
@@ -30,6 +30,7 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
messageFilter
.
insert
(
MAVLINK_MSG_ID_MISSION_ACK
,
false
);
messageFilter
.
insert
(
MAVLINK_MSG_ID_DATA_STREAM
,
false
);
messageFilter
.
insert
(
MAVLINK_MSG_ID_GPS_STATUS
,
false
);
messageFilter
.
insert
(
MAVLINK_MSG_ID_RC_CHANNELS_RAW
,
false
);
#ifdef MAVLINK_MSG_ID_ENCAPSULATED_DATA
messageFilter
.
insert
(
MAVLINK_MSG_ID_ENCAPSULATED_DATA
,
false
);
#endif
...
...
@@ -240,6 +241,30 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
name
=
QString
(
buf
);
time
=
getUnixTimeFromMs
(
msg
->
sysid
,
debug
.
time_boot_ms
);
}
else
if
(
msgid
==
MAVLINK_MSG_ID_RC_CHANNELS_RAW
)
{
// XXX this is really ugly, but we do not know a better way to do this
mavlink_rc_channels_raw_t
raw
;
mavlink_msg_rc_channels_raw_decode
(
msg
,
&
raw
);
name
=
name
.
arg
(
messageInfo
[
msgid
].
name
).
arg
(
fieldName
);
name
.
prepend
(
QString
(
"port%1_"
).
arg
(
raw
.
port
));
}
else
if
(
msgid
==
MAVLINK_MSG_ID_RC_CHANNELS_SCALED
)
{
// XXX this is really ugly, but we do not know a better way to do this
mavlink_rc_channels_scaled_t
scaled
;
mavlink_msg_rc_channels_scaled_decode
(
msg
,
&
scaled
);
name
=
name
.
arg
(
messageInfo
[
msgid
].
name
).
arg
(
fieldName
);
name
.
prepend
(
QString
(
"port%1_"
).
arg
(
scaled
.
port
));
}
else
if
(
msgid
==
MAVLINK_MSG_ID_SERVO_OUTPUT_RAW
)
{
// XXX this is really ugly, but we do not know a better way to do this
mavlink_servo_output_raw_t
servo
;
mavlink_msg_rc_channels_scaled_decode
(
msg
,
&
servo
);
name
=
name
.
arg
(
messageInfo
[
msgid
].
name
).
arg
(
fieldName
);
name
.
prepend
(
QString
(
"port%1_"
).
arg
(
servo
.
port
));
}
else
{
name
=
name
.
arg
(
messageInfo
[
msgid
].
name
).
arg
(
fieldName
);
...
...
src/ui/QGCPX4VehicleConfig.cc
View file @
f2678c5c
...
...
@@ -127,6 +127,26 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
ui
->
radio7Widget
->
setName
(
"Radio 7"
);
ui
->
radio8Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio8Widget
->
setName
(
"Radio 8"
);
ui
->
radio9Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio9Widget
->
setName
(
"Radio 9"
);
ui
->
radio10Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio10Widget
->
setName
(
"Radio 10"
);
ui
->
radio11Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio11Widget
->
setName
(
"Radio 11"
);
ui
->
radio12Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio12Widget
->
setName
(
"Radio 12"
);
ui
->
radio13Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio13Widget
->
setName
(
"Radio 13"
);
ui
->
radio14Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio14Widget
->
setName
(
"Radio 14"
);
ui
->
radio15Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio15Widget
->
setName
(
"Radio 15"
);
ui
->
radio16Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio16Widget
->
setName
(
"Radio 16"
);
ui
->
radio17Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio17Widget
->
setName
(
"Radio 17"
);
ui
->
radio18Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio18Widget
->
setName
(
"Radio 18"
);
connect
(
ui
->
rcMenuButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
rcMenuButtonClicked
()));
...
...
@@ -488,6 +508,16 @@ void QGCPX4VehicleConfig::startCalibrationRC()
ui
->
radio6Widget
->
showMinMax
();
ui
->
radio7Widget
->
showMinMax
();
ui
->
radio8Widget
->
showMinMax
();
ui
->
radio9Widget
->
showMinMax
();
ui
->
radio10Widget
->
showMinMax
();
ui
->
radio11Widget
->
showMinMax
();
ui
->
radio12Widget
->
showMinMax
();
ui
->
radio13Widget
->
showMinMax
();
ui
->
radio14Widget
->
showMinMax
();
ui
->
radio15Widget
->
showMinMax
();
ui
->
radio16Widget
->
showMinMax
();
ui
->
radio17Widget
->
showMinMax
();
ui
->
radio18Widget
->
showMinMax
();
QMessageBox
::
information
(
0
,
tr
(
"Information"
),
tr
(
"Please click on the <Finish RC Calibration> button once finished"
));
}
...
...
@@ -516,6 +546,16 @@ void QGCPX4VehicleConfig::stopCalibrationRC()
ui
->
radio6Widget
->
hideMinMax
();
ui
->
radio7Widget
->
hideMinMax
();
ui
->
radio8Widget
->
hideMinMax
();
ui
->
radio9Widget
->
hideMinMax
();
ui
->
radio10Widget
->
hideMinMax
();
ui
->
radio11Widget
->
hideMinMax
();
ui
->
radio12Widget
->
hideMinMax
();
ui
->
radio13Widget
->
hideMinMax
();
ui
->
radio14Widget
->
hideMinMax
();
ui
->
radio15Widget
->
hideMinMax
();
ui
->
radio16Widget
->
hideMinMax
();
ui
->
radio17Widget
->
hideMinMax
();
ui
->
radio18Widget
->
hideMinMax
();
for
(
unsigned
int
i
=
0
;
i
<
chanCount
;
i
++
)
{
if
(
rcMin
[
i
]
>
1350
)
{
...
...
@@ -1517,6 +1557,36 @@ void QGCPX4VehicleConfig::updateMappingView(int function_index)
case
7
:
ui
->
radio8Widget
->
setName
(
tr
(
"%1 (#8)"
).
arg
(
assignments
[
7
]));
break
;
case
8
:
ui
->
radio9Widget
->
setName
(
tr
(
"%1 (#9)"
).
arg
(
assignments
[
8
]));
break
;
case
9
:
ui
->
radio10Widget
->
setName
(
tr
(
"%1 (#10)"
).
arg
(
assignments
[
9
]));
break
;
case
10
:
ui
->
radio11Widget
->
setName
(
tr
(
"%1 (#11)"
).
arg
(
assignments
[
10
]));
break
;
case
11
:
ui
->
radio12Widget
->
setName
(
tr
(
"%1 (#12)"
).
arg
(
assignments
[
11
]));
break
;
case
12
:
ui
->
radio13Widget
->
setName
(
tr
(
"%1 (#13)"
).
arg
(
assignments
[
12
]));
break
;
case
13
:
ui
->
radio14Widget
->
setName
(
tr
(
"%1 (#14)"
).
arg
(
assignments
[
13
]));
break
;
case
14
:
ui
->
radio15Widget
->
setName
(
tr
(
"%1 (#15)"
).
arg
(
assignments
[
14
]));
break
;
case
15
:
ui
->
radio16Widget
->
setName
(
tr
(
"%1 (#16)"
).
arg
(
assignments
[
15
]));
break
;
case
16
:
ui
->
radio17Widget
->
setName
(
tr
(
"%1 (#17)"
).
arg
(
assignments
[
16
]));
break
;
case
17
:
ui
->
radio18Widget
->
setName
(
tr
(
"%1 (#18)"
).
arg
(
assignments
[
17
]));
break
;
}
}
}
...
...
@@ -1778,6 +1848,16 @@ void QGCPX4VehicleConfig::updateRcWidgetValues()
ui
->
radio6Widget
->
setValueAndRange
(
rcValueReversed
[
5
],
rcMin
[
5
],
rcMax
[
5
]);
ui
->
radio7Widget
->
setValueAndRange
(
rcValueReversed
[
6
],
rcMin
[
6
],
rcMax
[
6
]);
ui
->
radio8Widget
->
setValueAndRange
(
rcValueReversed
[
7
],
rcMin
[
7
],
rcMax
[
7
]);
ui
->
radio9Widget
->
setValueAndRange
(
rcValueReversed
[
8
],
rcMin
[
8
],
rcMax
[
8
]);
ui
->
radio10Widget
->
setValueAndRange
(
rcValueReversed
[
9
],
rcMin
[
9
],
rcMax
[
9
]);
ui
->
radio11Widget
->
setValueAndRange
(
rcValueReversed
[
10
],
rcMin
[
10
],
rcMax
[
10
]);
ui
->
radio12Widget
->
setValueAndRange
(
rcValueReversed
[
11
],
rcMin
[
11
],
rcMax
[
11
]);
ui
->
radio13Widget
->
setValueAndRange
(
rcValueReversed
[
12
],
rcMin
[
12
],
rcMax
[
12
]);
ui
->
radio14Widget
->
setValueAndRange
(
rcValueReversed
[
13
],
rcMin
[
13
],
rcMax
[
13
]);
ui
->
radio15Widget
->
setValueAndRange
(
rcValueReversed
[
14
],
rcMin
[
14
],
rcMax
[
14
]);
ui
->
radio16Widget
->
setValueAndRange
(
rcValueReversed
[
15
],
rcMin
[
15
],
rcMax
[
15
]);
ui
->
radio17Widget
->
setValueAndRange
(
rcValueReversed
[
16
],
rcMin
[
16
],
rcMax
[
16
]);
ui
->
radio18Widget
->
setValueAndRange
(
rcValueReversed
[
17
],
rcMin
[
17
],
rcMax
[
17
]);
}
void
QGCPX4VehicleConfig
::
updateRcChanLabels
()
...
...
src/ui/QGCPX4VehicleConfig.h
View file @
f2678c5c
...
...
@@ -277,7 +277,7 @@ protected:
bool
doneLoadingConfig
;
UASInterface
*
mav
;
///< The current MAV
QGCUASParamManagerInterface
*
paramMgr
;
///< params mgr for the mav
static
const
unsigned
int
chanMax
=
1
4
;
///< Maximum number of channels
static
const
unsigned
int
chanMax
=
1
8
;
///< Maximum number of channels
static
const
unsigned
int
chanMappedMax
=
16
;
///< Maximum number of mapped channels (can be higher than input channel count)
unsigned
int
chanCount
;
///< Actual channels
float
rcMin
[
chanMax
];
///< Minimum values
...
...
src/ui/QGCPX4VehicleConfig.ui
View file @
f2678c5c
This diff is collapsed.
Click to expand it.
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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