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
48f06761
Commit
48f06761
authored
Dec 31, 2013
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #454 from mavlink/rc_config
Extended RC config to 18 channels, dealing with multi-port messages
parents
9a33de6d
88b9528b
Changes
5
Show whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
487 additions
and
247 deletions
+487
-247
UAS.cc
src/uas/UAS.cc
+39
-17
MAVLinkDecoder.cc
src/ui/MAVLinkDecoder.cc
+25
-0
QGCPX4VehicleConfig.cc
src/ui/QGCPX4VehicleConfig.cc
+80
-0
QGCPX4VehicleConfig.h
src/ui/QGCPX4VehicleConfig.h
+2
-2
QGCPX4VehicleConfig.ui
src/ui/QGCPX4VehicleConfig.ui
+341
-228
No files found.
src/uas/UAS.cc
View file @
48f06761
...
@@ -1001,30 +1001,52 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -1001,30 +1001,52 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
{
mavlink_rc_channels_raw_t
channels
;
mavlink_rc_channels_raw_t
channels
;
mavlink_msg_rc_channels_raw_decode
(
&
message
,
&
channels
);
mavlink_msg_rc_channels_raw_decode
(
&
message
,
&
channels
);
const
unsigned
int
portWidth
=
8
;
// XXX magic number
emit
remoteControlRSSIChanged
(
channels
.
rssi
/
255.0
f
);
emit
remoteControlRSSIChanged
(
channels
.
rssi
/
255.0
f
);
emit
remoteControlChannelRawChanged
(
0
,
channels
.
chan1_raw
);
if
(
channels
.
chan1_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
1
,
channels
.
chan2_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
0
,
channels
.
chan1_raw
);
emit
remoteControlChannelRawChanged
(
2
,
channels
.
chan3_raw
);
if
(
channels
.
chan2_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
3
,
channels
.
chan4_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
1
,
channels
.
chan2_raw
);
emit
remoteControlChannelRawChanged
(
4
,
channels
.
chan5_raw
);
if
(
channels
.
chan3_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
5
,
channels
.
chan6_raw
);
emit
remoteControlChannelRawChanged
(
channels
.
port
*
portWidth
+
2
,
channels
.
chan3_raw
);
emit
remoteControlChannelRawChanged
(
6
,
channels
.
chan7_raw
);
if
(
channels
.
chan4_raw
!=
UINT16_MAX
)
emit
remoteControlChannelRawChanged
(
7
,
channels
.
chan8_raw
);
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
;
break
;
case
MAVLINK_MSG_ID_RC_CHANNELS_SCALED
:
case
MAVLINK_MSG_ID_RC_CHANNELS_SCALED
:
{
{
mavlink_rc_channels_scaled_t
channels
;
mavlink_rc_channels_scaled_t
channels
;
mavlink_msg_rc_channels_scaled_decode
(
&
message
,
&
channels
);
mavlink_msg_rc_channels_scaled_decode
(
&
message
,
&
channels
);
const
unsigned
int
portWidth
=
8
;
// XXX magic number
emit
remoteControlRSSIChanged
(
channels
.
rssi
/
255.0
f
);
emit
remoteControlRSSIChanged
(
channels
.
rssi
/
255.0
f
);
emit
remoteControlChannelScaledChanged
(
0
,
channels
.
chan1_scaled
/
10000.0
f
);
if
(
channels
.
chan1_scaled
!=
UINT16_MAX
)
emit
remoteControlChannelScaledChanged
(
1
,
channels
.
chan2_scaled
/
10000.0
f
);
emit
remoteControlChannelScaledChanged
(
channels
.
port
*
portWidth
+
0
,
channels
.
chan1_scaled
/
10000.0
f
);
emit
remoteControlChannelScaledChanged
(
2
,
channels
.
chan3_scaled
/
10000.0
f
);
if
(
channels
.
chan2_scaled
!=
UINT16_MAX
)
emit
remoteControlChannelScaledChanged
(
3
,
channels
.
chan4_scaled
/
10000.0
f
);
emit
remoteControlChannelScaledChanged
(
channels
.
port
*
portWidth
+
1
,
channels
.
chan2_scaled
/
10000.0
f
);
emit
remoteControlChannelScaledChanged
(
4
,
channels
.
chan5_scaled
/
10000.0
f
);
if
(
channels
.
chan3_scaled
!=
UINT16_MAX
)
emit
remoteControlChannelScaledChanged
(
5
,
channels
.
chan6_scaled
/
10000.0
f
);
emit
remoteControlChannelScaledChanged
(
channels
.
port
*
portWidth
+
2
,
channels
.
chan3_scaled
/
10000.0
f
);
emit
remoteControlChannelScaledChanged
(
6
,
channels
.
chan7_scaled
/
10000.0
f
);
if
(
channels
.
chan4_scaled
!=
UINT16_MAX
)
emit
remoteControlChannelScaledChanged
(
7
,
channels
.
chan8_scaled
/
10000.0
f
);
emit
remoteControlChannelScaledChanged
(
channels
.
port
*
portWidth
+
3
,
channels
.
chan4_scaled
/
10000.0
f
);
if
(
channels
.
chan5_scaled
!=
UINT16_MAX
)
emit
remoteControlChannelScaledChanged
(
channels
.
port
*
portWidth
+
4
,
channels
.
chan5_scaled
/
10000.0
f
);
if
(
channels
.
chan6_scaled
!=
UINT16_MAX
)
emit
remoteControlChannelScaledChanged
(
channels
.
port
*
portWidth
+
5
,
channels
.
chan6_scaled
/
10000.0
f
);
if
(
channels
.
chan7_scaled
!=
UINT16_MAX
)
emit
remoteControlChannelScaledChanged
(
channels
.
port
*
portWidth
+
6
,
channels
.
chan7_scaled
/
10000.0
f
);
if
(
channels
.
chan8_scaled
!=
UINT16_MAX
)
emit
remoteControlChannelScaledChanged
(
channels
.
port
*
portWidth
+
7
,
channels
.
chan8_scaled
/
10000.0
f
);
}
}
break
;
break
;
case
MAVLINK_MSG_ID_PARAM_VALUE
:
case
MAVLINK_MSG_ID_PARAM_VALUE
:
...
@@ -1207,7 +1229,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -1207,7 +1229,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_servo_output_raw_t raw;
mavlink_servo_output_raw_t raw;
mavlink_msg_servo_output_raw_decode(&message, &raw);
mavlink_msg_servo_output_raw_decode(&message, &raw);
if (hilEnabled)
if (hilEnabled
&& raw.port == 0
)
{
{
emit hilActuatorsChanged(static_cast<uint64_t>(getUnixTimeFromMs(raw.time_usec)), static_cast<float>(raw.servo1_raw),
emit hilActuatorsChanged(static_cast<uint64_t>(getUnixTimeFromMs(raw.time_usec)), static_cast<float>(raw.servo1_raw),
static_cast<float>(raw.servo2_raw), static_cast<float>(raw.servo3_raw),
static_cast<float>(raw.servo2_raw), static_cast<float>(raw.servo3_raw),
...
...
src/ui/MAVLinkDecoder.cc
View file @
48f06761
...
@@ -30,6 +30,7 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
...
@@ -30,6 +30,7 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
messageFilter
.
insert
(
MAVLINK_MSG_ID_MISSION_ACK
,
false
);
messageFilter
.
insert
(
MAVLINK_MSG_ID_MISSION_ACK
,
false
);
messageFilter
.
insert
(
MAVLINK_MSG_ID_DATA_STREAM
,
false
);
messageFilter
.
insert
(
MAVLINK_MSG_ID_DATA_STREAM
,
false
);
messageFilter
.
insert
(
MAVLINK_MSG_ID_GPS_STATUS
,
false
);
messageFilter
.
insert
(
MAVLINK_MSG_ID_GPS_STATUS
,
false
);
messageFilter
.
insert
(
MAVLINK_MSG_ID_RC_CHANNELS_RAW
,
false
);
#ifdef MAVLINK_MSG_ID_ENCAPSULATED_DATA
#ifdef MAVLINK_MSG_ID_ENCAPSULATED_DATA
messageFilter
.
insert
(
MAVLINK_MSG_ID_ENCAPSULATED_DATA
,
false
);
messageFilter
.
insert
(
MAVLINK_MSG_ID_ENCAPSULATED_DATA
,
false
);
#endif
#endif
...
@@ -240,6 +241,30 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
...
@@ -240,6 +241,30 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
name
=
QString
(
buf
);
name
=
QString
(
buf
);
time
=
getUnixTimeFromMs
(
msg
->
sysid
,
debug
.
time_boot_ms
);
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_servo_output_raw_decode
(
msg
,
&
servo
);
name
=
name
.
arg
(
messageInfo
[
msgid
].
name
).
arg
(
fieldName
);
name
.
prepend
(
QString
(
"port%1_"
).
arg
(
servo
.
port
));
}
else
else
{
{
name
=
name
.
arg
(
messageInfo
[
msgid
].
name
).
arg
(
fieldName
);
name
=
name
.
arg
(
messageInfo
[
msgid
].
name
).
arg
(
fieldName
);
...
...
src/ui/QGCPX4VehicleConfig.cc
View file @
48f06761
...
@@ -127,6 +127,26 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
...
@@ -127,6 +127,26 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
ui
->
radio7Widget
->
setName
(
"Radio 7"
);
ui
->
radio7Widget
->
setName
(
"Radio 7"
);
ui
->
radio8Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio8Widget
->
setOrientation
(
Qt
::
Horizontal
);
ui
->
radio8Widget
->
setName
(
"Radio 8"
);
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
()),
connect
(
ui
->
rcMenuButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
rcMenuButtonClicked
()));
this
,
SLOT
(
rcMenuButtonClicked
()));
...
@@ -488,6 +508,16 @@ void QGCPX4VehicleConfig::startCalibrationRC()
...
@@ -488,6 +508,16 @@ void QGCPX4VehicleConfig::startCalibrationRC()
ui
->
radio6Widget
->
showMinMax
();
ui
->
radio6Widget
->
showMinMax
();
ui
->
radio7Widget
->
showMinMax
();
ui
->
radio7Widget
->
showMinMax
();
ui
->
radio8Widget
->
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"
));
QMessageBox
::
information
(
0
,
tr
(
"Information"
),
tr
(
"Please click on the <Finish RC Calibration> button once finished"
));
}
}
...
@@ -516,6 +546,16 @@ void QGCPX4VehicleConfig::stopCalibrationRC()
...
@@ -516,6 +546,16 @@ void QGCPX4VehicleConfig::stopCalibrationRC()
ui
->
radio6Widget
->
hideMinMax
();
ui
->
radio6Widget
->
hideMinMax
();
ui
->
radio7Widget
->
hideMinMax
();
ui
->
radio7Widget
->
hideMinMax
();
ui
->
radio8Widget
->
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
++
)
{
for
(
unsigned
int
i
=
0
;
i
<
chanCount
;
i
++
)
{
if
(
rcMin
[
i
]
>
1350
)
{
if
(
rcMin
[
i
]
>
1350
)
{
...
@@ -1517,6 +1557,36 @@ void QGCPX4VehicleConfig::updateMappingView(int function_index)
...
@@ -1517,6 +1557,36 @@ void QGCPX4VehicleConfig::updateMappingView(int function_index)
case
7
:
case
7
:
ui
->
radio8Widget
->
setName
(
tr
(
"%1 (#8)"
).
arg
(
assignments
[
7
]));
ui
->
radio8Widget
->
setName
(
tr
(
"%1 (#8)"
).
arg
(
assignments
[
7
]));
break
;
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()
...
@@ -1778,6 +1848,16 @@ void QGCPX4VehicleConfig::updateRcWidgetValues()
ui
->
radio6Widget
->
setValueAndRange
(
rcValueReversed
[
5
],
rcMin
[
5
],
rcMax
[
5
]);
ui
->
radio6Widget
->
setValueAndRange
(
rcValueReversed
[
5
],
rcMin
[
5
],
rcMax
[
5
]);
ui
->
radio7Widget
->
setValueAndRange
(
rcValueReversed
[
6
],
rcMin
[
6
],
rcMax
[
6
]);
ui
->
radio7Widget
->
setValueAndRange
(
rcValueReversed
[
6
],
rcMin
[
6
],
rcMax
[
6
]);
ui
->
radio8Widget
->
setValueAndRange
(
rcValueReversed
[
7
],
rcMin
[
7
],
rcMax
[
7
]);
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
()
void
QGCPX4VehicleConfig
::
updateRcChanLabels
()
...
...
src/ui/QGCPX4VehicleConfig.h
View file @
48f06761
...
@@ -277,8 +277,8 @@ protected:
...
@@ -277,8 +277,8 @@ protected:
bool
doneLoadingConfig
;
bool
doneLoadingConfig
;
UASInterface
*
mav
;
///< The current MAV
UASInterface
*
mav
;
///< The current MAV
QGCUASParamManagerInterface
*
paramMgr
;
///< params mgr for the 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
=
1
6
;
///< Maximum number of mapped channels (can be higher than input channel count)
static
const
unsigned
int
chanMappedMax
=
1
8
;
///< Maximum number of mapped channels (can be higher than input channel count)
unsigned
int
chanCount
;
///< Actual channels
unsigned
int
chanCount
;
///< Actual channels
float
rcMin
[
chanMax
];
///< Minimum values
float
rcMin
[
chanMax
];
///< Minimum values
float
rcMax
[
chanMax
];
///< Maximum values
float
rcMax
[
chanMax
];
///< Maximum values
...
...
src/ui/QGCPX4VehicleConfig.ui
View file @
48f06761
...
@@ -6,8 +6,8 @@
...
@@ -6,8 +6,8 @@
<rect>
<rect>
<x>
0
</x>
<x>
0
</x>
<y>
0
</y>
<y>
0
</y>
<width>
12
56
</width>
<width>
12
72
</width>
<height>
1
009
</height>
<height>
1
132
</height>
</rect>
</rect>
</property>
</property>
<property
name=
"sizePolicy"
>
<property
name=
"sizePolicy"
>
...
@@ -48,231 +48,8 @@
...
@@ -48,231 +48,8 @@
<layout
class=
"QVBoxLayout"
name=
"firmwareLayout"
/>
<layout
class=
"QVBoxLayout"
name=
"firmwareLayout"
/>
</widget>
</widget>
<widget
class=
"QWidget"
name=
"rcTab"
>
<widget
class=
"QWidget"
name=
"rcTab"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_17"
>
<layout
class=
"QGridLayout"
name=
"gridLayout_4"
>
<item>
<item
row=
"4"
column=
"0"
>
<layout
class=
"QGridLayout"
name=
"gridLayout"
rowstretch=
"0,0"
columnstretch=
"0,0,0,0"
>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QGCRadioChannelDisplay"
name=
"throttleWidget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
50
</width>
<height>
200
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
50
</width>
<height>
200
</height>
</size>
</property>
</widget>
</item>
<item
row=
"1"
column=
"2"
>
<widget
class=
"QGCRadioChannelDisplay"
name=
"rollWidget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QGCRadioChannelDisplay"
name=
"pitchWidget"
native=
"true"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Preferred"
vsizetype=
"Preferred"
>
<horstretch>
1
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"minimumSize"
>
<size>
<width>
50
</width>
<height>
200
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
50
</width>
<height>
200
</height>
</size>
</property>
</widget>
</item>
<item
row=
"0"
column=
"3"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_6"
>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio5Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio6Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio7Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio8Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
</layout>
</item>
<item
row=
"1"
column=
"1"
>
<widget
class=
"QGCRadioChannelDisplay"
name=
"yawWidget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_9"
>
<item>
<widget
class=
"QPushButton"
name=
"rcCalibrationButton"
>
<property
name=
"text"
>
<string>
Start Calibration
</string>
</property>
</widget>
</item>
<item>
<spacer
name=
"verticalSpacer_3"
>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
</property>
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<width>
20
</width>
<height>
40
</height>
</size>
</property>
</spacer>
</item>
<item>
<widget
class=
"QGroupBox"
name=
"groupBox"
>
<property
name=
"title"
>
<string>
Spektrum RC
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_10"
>
<item>
<widget
class=
"QPushButton"
name=
"spektrumPairButton"
>
<property
name=
"text"
>
<string>
Pair Receiver
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QRadioButton"
name=
"dsm2RadioButton"
>
<property
name=
"text"
>
<string>
DSM2 Mode
</string>
</property>
<property
name=
"checked"
>
<bool>
true
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QRadioButton"
name=
"dsmxRadioButton"
>
<property
name=
"text"
>
<string>
DSMX Mode (3 to 7 channels)
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QRadioButton"
name=
"dsmx8RadioButton"
>
<property
name=
"text"
>
<string>
DSMX Mode (8 or more channels)
</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item>
<widget
class=
"QLabel"
name=
"rcLabel"
>
<property
name=
"text"
>
<string>
Waiting for RC channel data..
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QCheckBox"
name=
"advancedCheckBox"
>
<property
name=
"text"
>
<string>
Show Advanced Configuration Options
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QGraphicsView"
name=
"graphicsView"
/>
</item>
<item>
<widget
class=
"QGroupBox"
name=
"advancedGroupBox"
>
<widget
class=
"QGroupBox"
name=
"advancedGroupBox"
>
<property
name=
"title"
>
<property
name=
"title"
>
<string>
Stick to Channel Mapping and Reverse
</string>
<string>
Stick to Channel Mapping and Reverse
</string>
...
@@ -828,7 +605,7 @@
...
@@ -828,7 +605,7 @@
</layout>
</layout>
</widget>
</widget>
</item>
</item>
<item>
<item
row=
"5"
column=
"0"
>
<spacer
name=
"verticalSpacer"
>
<spacer
name=
"verticalSpacer"
>
<property
name=
"orientation"
>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
<enum>
Qt::Vertical
</enum>
...
@@ -841,6 +618,342 @@
...
@@ -841,6 +618,342 @@
</property>
</property>
</spacer>
</spacer>
</item>
</item>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QGridLayout"
name=
"gridLayout"
rowstretch=
"0,0"
columnstretch=
"0,0,0,0"
>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QGCRadioChannelDisplay"
name=
"throttleWidget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
50
</width>
<height>
200
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
50
</width>
<height>
200
</height>
</size>
</property>
</widget>
</item>
<item
row=
"1"
column=
"2"
>
<widget
class=
"QGCRadioChannelDisplay"
name=
"rollWidget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QGCRadioChannelDisplay"
name=
"pitchWidget"
native=
"true"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Preferred"
vsizetype=
"Preferred"
>
<horstretch>
1
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"minimumSize"
>
<size>
<width>
50
</width>
<height>
200
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
50
</width>
<height>
200
</height>
</size>
</property>
</widget>
</item>
<item
row=
"1"
column=
"1"
>
<widget
class=
"QGCRadioChannelDisplay"
name=
"yawWidget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_9"
>
<item>
<widget
class=
"QPushButton"
name=
"rcCalibrationButton"
>
<property
name=
"text"
>
<string>
Start Calibration
</string>
</property>
</widget>
</item>
<item>
<spacer
name=
"verticalSpacer_3"
>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
</property>
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<width>
20
</width>
<height>
40
</height>
</size>
</property>
</spacer>
</item>
<item>
<widget
class=
"QGroupBox"
name=
"groupBox"
>
<property
name=
"title"
>
<string>
Spektrum RC
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_10"
>
<item>
<widget
class=
"QPushButton"
name=
"spektrumPairButton"
>
<property
name=
"text"
>
<string>
Pair Receiver
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QRadioButton"
name=
"dsm2RadioButton"
>
<property
name=
"text"
>
<string>
DSM2 Mode
</string>
</property>
<property
name=
"checked"
>
<bool>
true
</bool>
</property>
</widget>
</item>
<item>
<widget
class=
"QRadioButton"
name=
"dsmxRadioButton"
>
<property
name=
"text"
>
<string>
DSMX Mode (3 to 7 channels)
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QRadioButton"
name=
"dsmx8RadioButton"
>
<property
name=
"text"
>
<string>
DSMX Mode (8 or more channels)
</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item
row=
"2"
column=
"0"
>
<widget
class=
"QCheckBox"
name=
"advancedCheckBox"
>
<property
name=
"text"
>
<string>
Show Advanced Configuration Options
</string>
</property>
</widget>
</item>
<item
row=
"3"
column=
"0"
>
<widget
class=
"QGraphicsView"
name=
"graphicsView"
/>
</item>
<item
row=
"1"
column=
"0"
>
<widget
class=
"QLabel"
name=
"rcLabel"
>
<property
name=
"text"
>
<string>
Waiting for RC channel data..
</string>
</property>
</widget>
</item>
<item
row=
"0"
column=
"1"
rowspan=
"5"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_6"
>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio5Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio6Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio7Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio8Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio9Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio10Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio11Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio12Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio13Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio14Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio15Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio16Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio17Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QGCRadioChannelDisplay"
name=
"radio18Widget"
native=
"true"
>
<property
name=
"minimumSize"
>
<size>
<width>
250
</width>
<height>
40
</height>
</size>
</property>
</widget>
</item>
<item>
<spacer
name=
"verticalSpacer_4"
>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
</property>
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<width>
20
</width>
<height>
40
</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>
</layout>
</widget>
</widget>
<widget
class=
"QWidget"
name=
"sensorTab"
>
<widget
class=
"QWidget"
name=
"sensorTab"
>
...
...
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