Commit d8ec1c38 authored by Lorenz Meier's avatar Lorenz Meier

Improving RC ui

parent 3ffc6835
......@@ -469,15 +469,10 @@ void QGCPX4VehicleConfig::startCalibrationRC()
identifyChannelMapping(i);
}
// Try to identify inverted channels, but only for R/P/Y/T
for (int i = 0; i < 4; i++) {
detectChannelInversion(i);
}
//QMessageBox::information(0,"Information","Additional channels have not been mapped, but can be mapped in the channel table below.");
configEnabled = false;
QMessageBox::information(0,"Information","Click OK, then move all sticks to their extreme positions, watching the min/max values to ensure you get the most range from your controller. This includes all switches");
ui->rcCalibrationButton->setText(tr("Save RC Calibration"));
QMessageBox::information(0, tr("Information"),tr("Click OK, then move all sticks to their extreme positions, watching the min/max values to ensure you get the most range from your controller. This includes all switches"));
ui->rcCalibrationButton->setText(tr("Finish RC Calibration"));
resetCalibrationRC();
calibrationEnabled = true;
ui->rollWidget->showMinMax();
......@@ -488,6 +483,8 @@ void QGCPX4VehicleConfig::startCalibrationRC()
ui->radio6Widget->showMinMax();
ui->radio7Widget->showMinMax();
ui->radio8Widget->showMinMax();
QMessageBox::information(0, tr("Information"), tr("Please click on the <Finish RC Calibration> button once finished"));
}
void QGCPX4VehicleConfig::stopCalibrationRC()
......@@ -495,6 +492,11 @@ void QGCPX4VehicleConfig::stopCalibrationRC()
if (!calibrationEnabled)
return;
// Try to identify inverted channels, but only for R/P/Y/T
for (int i = 0; i < 4; i++) {
detectChannelInversion(i);
}
QMessageBox::information(0,"Trims","Ensure all controls are centered and throttle is in the lowest position. Click OK to continue");
calibrationEnabled = false;
......
......@@ -198,30 +198,6 @@
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="spektrumPairButton">
<property name="text">
<string>Spektrum RC Pairing</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</string>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
......@@ -235,6 +211,39 @@
</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</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
</layout>
......@@ -870,8 +879,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>98</width>
<height>28</height>
<width>16</width>
<height>16</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_4">
......@@ -907,8 +916,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>98</width>
<height>28</height>
<width>16</width>
<height>16</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_5">
......@@ -958,8 +967,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>98</width>
<height>28</height>
<width>16</width>
<height>16</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_7">
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment