Commit 514741a4 authored by Lorenz Meier's avatar Lorenz Meier

Supporting RC config better for PX4 vehicles, no functionality changes for other systems

parent 79b910ab
......@@ -1657,11 +1657,11 @@ void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
#endif
}
void UAS::startRadioControlCalibration()
void UAS::startRadioControlCalibration(int param)
{
mavlink_message_t msg;
// Param 1: gyro cal, param 2: mag cal, param 3: pressure cal, Param 4: radio
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, 1, 0, 0, 0);
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_CALIBRATION, 1, 0, 0, 0, param, 0, 0, 0);
sendMessage(msg);
}
......
......@@ -911,7 +911,7 @@ public slots:
/** @brief Add an offset in body frame to the setpoint */
void setLocalPositionOffset(float x, float y, float z, float yaw);
void startRadioControlCalibration();
void startRadioControlCalibration(int param=1);
void endRadioControlCalibration();
void startMagnetometerCalibration();
void startGyroscopeCalibration();
......
......@@ -370,7 +370,7 @@ public slots:
virtual void setLocalPositionSetpoint(float x, float y, float z, float yaw) = 0;
virtual void setLocalPositionOffset(float x, float y, float z, float yaw) = 0;
virtual void startRadioControlCalibration() = 0;
virtual void startRadioControlCalibration(int param=1) = 0;
virtual void endRadioControlCalibration() = 0;
virtual void startMagnetometerCalibration() = 0;
virtual void startGyroscopeCalibration() = 0;
......
......@@ -150,6 +150,8 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
connect(ui->rcMenuButton,SIGNAL(clicked()),
this,SLOT(rcMenuButtonClicked()));
connect(ui->rcCopyTrimButton, SIGNAL(clicked()),
this, SLOT(copyAttitudeTrim()));
connect(ui->sensorMenuButton,SIGNAL(clicked()),
this,SLOT(sensorMenuButtonClicked()));
connect(ui->generalMenuButton,SIGNAL(clicked()),
......@@ -381,6 +383,33 @@ void QGCPX4VehicleConfig::toggleSpektrumPairing(bool enabled)
}
}
void QGCPX4VehicleConfig::copyAttitudeTrim() {
if (configEnabled) {
QMessageBox warnMsgBox;
warnMsgBox.setText(tr("Attitude trim denied during RC calibration"));
warnMsgBox.setInformativeText(tr("Please end the RC calibration before doing attitude trim."));
warnMsgBox.setStandardButtons(QMessageBox::Ok);
warnMsgBox.setDefaultButton(QMessageBox::Ok);
(void)warnMsgBox.exec();
}
// Not aborted, but warn user
msgBox.setText(tr("Confirm Attitude Trim"));
msgBox.setInformativeText(tr("On clicking OK, the current Roll / Pitch / Yaw stick positions will be set as trim values in auto flight. Do NOT reset your trim values after this step."));
msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel);//allow user to cancel upload after reviewing values
int msgBoxResult = msgBox.exec();
if (QMessageBox::Cancel == msgBoxResult) {
return;
// do not execute
}
mav->startRadioControlCalibration(2);
QGC::SLEEP::msleep(100);
mav->endRadioControlCalibration();
}
void QGCPX4VehicleConfig::setTrimPositions()
{
int rollMap = rcMapping[0];
......@@ -473,7 +502,7 @@ void QGCPX4VehicleConfig::detectChannelInversion(int aert_index)
void QGCPX4VehicleConfig::startCalibrationRC()
{
if (chanCount < 5) {
if (chanCount < 5 && !mav) {
QMessageBox::warning(0,
tr("RC not Connected"),
tr("Is the RC receiver connected and transmitter turned on? Detected %1 radio channels. To operate PX4, you need at least 5 channels. ").arg(chanCount));
......@@ -481,7 +510,8 @@ void QGCPX4VehicleConfig::startCalibrationRC()
return;
}
mav->startRadioControlCalibration();
// XXX magic number: Set to 1 for radio input disable
mav->startRadioControlCalibration(1);
// reset all channel mappings above Ch 5 to invalid/unused value before starting calibration
for (unsigned int j= 5; j < chanMappedMax; j++) {
......@@ -500,7 +530,6 @@ void QGCPX4VehicleConfig::startCalibrationRC()
//QMessageBox::information(0,"Information","Additional channels have not been mapped, but can be mapped in the channel table below.");
configEnabled = false;
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;
......@@ -523,7 +552,15 @@ void QGCPX4VehicleConfig::startCalibrationRC()
ui->radio17Widget->showMinMax();
ui->radio18Widget->showMinMax();
QMessageBox::information(0, tr("Information"), tr("Please click on the <Finish RC Calibration> button once finished"));
msgBox.setText(tr("Information"));
msgBox.setInformativeText(tr("Please move the sticks to their extreme positions, including all switches. Then click on the OK button once finished"));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.show();
msgBox.move((frameGeometry().width() - msgBox.width()) / 4.0f,(frameGeometry().height() - msgBox.height()) / 1.5f);
int msgBoxResult = msgBox.exec();
if (QMessageBox::Ok == msgBoxResult) {
stopCalibrationRC();
}
}
void QGCPX4VehicleConfig::stopCalibrationRC()
......@@ -531,18 +568,19 @@ void QGCPX4VehicleConfig::stopCalibrationRC()
if (!calibrationEnabled)
return;
mav->endRadioControlCalibration();
// 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");
QMessageBox::information(0,"Trims","Ensure THROTTLE is in the LOWEST position and roll / pitch / yaw are CENTERED. Click OK to continue");
calibrationEnabled = false;
configEnabled = false;
ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
ui->rcCalibrationButton->blockSignals(true);
ui->rcCalibrationButton->setChecked(false);
ui->rcCalibrationButton->blockSignals(false);
ui->rollWidget->hideMinMax();
ui->pitchWidget->hideMinMax();
......@@ -585,17 +623,20 @@ void QGCPX4VehicleConfig::stopCalibrationRC()
statusstr += QString::number(i) +"\t"+ QString::number(rcMin[i]) +"\t"+ QString::number(rcValue[i]) +"\t"+ QString::number(rcMax[i]) +"\n";
}
msgBox.setText(tr("Confirm Calibration"));
msgBox.setInformativeText(statusstr);
msgBox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel);//allow user to cancel upload after reviewing values
int msgBoxResult = msgBox.exec();
// Done, exit calibration mode now
mav->endRadioControlCalibration();
if (QMessageBox::Cancel == msgBoxResult) {
return;//don't commit these values
return; //don't commit these values
} else {
QMessageBox::information(0,"Uploading the RC Calibration","The configuration will now be uploaded and permanently stored.");
writeCalibrationRC();
}
QMessageBox::information(0,"Uploading the RC Calibration","The configuration will now be uploaded and permanently stored.");
writeCalibrationRC();
}
void QGCPX4VehicleConfig::loadQgcConfig(bool primary)
......
......@@ -62,6 +62,8 @@ public slots:
void toggleCalibrationRC(bool enabled);
/** Start/stop the Spektrum pair routine */
void toggleSpektrumPairing(bool enabled);
/** Set the current trim values as attitude trim values */
void copyAttitudeTrim();
/** Set trim positions */
void setTrimPositions();
/** Detect which channels need to be inverted */
......
......@@ -6,7 +6,7 @@
<rect>
<x>0</x>
<y>0</y>
<width>1272</width>
<width>1293</width>
<height>1132</height>
</rect>
</property>
......@@ -20,7 +20,16 @@
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout_3">
<property name="margin">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item row="1" column="1">
......@@ -619,7 +628,7 @@
</spacer>
</item>
<item row="0" column="0">
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0" columnstretch="0,0,0,0">
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0" columnstretch="0,0,0">
<item row="0" column="1">
<widget class="QGCRadioChannelDisplay" name="throttleWidget" native="true">
<property name="minimumSize">
......@@ -699,6 +708,16 @@
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="rcCopyTrimButton">
<property name="toolTip">
<string>Copy the trim values from roll / pitch / yaw from manual flight to the autonomous flight modes.</string>
</property>
<property name="text">
<string>Copy Attitude Trims</string>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
......@@ -986,7 +1005,16 @@
<string>Configuration</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
<property name="margin">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
......@@ -999,12 +1027,21 @@
<rect>
<x>0</x>
<y>0</y>
<width>16</width>
<height>16</height>
<width>98</width>
<height>28</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_4">
<property name="margin">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
......@@ -1023,7 +1060,16 @@
<string>Configuration</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_5">
<property name="margin">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
......@@ -1036,12 +1082,21 @@
<rect>
<x>0</x>
<y>0</y>
<width>16</width>
<height>16</height>
<width>98</width>
<height>28</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<property name="margin">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
......@@ -1074,7 +1129,16 @@
<string>Onboard Configuration</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<property name="margin">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
......@@ -1087,12 +1151,21 @@
<rect>
<x>0</x>
<y>0</y>
<width>16</width>
<height>16</height>
<width>98</width>
<height>28</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_7">
<property name="margin">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
......@@ -1198,7 +1271,16 @@
<item row="0" column="0" rowspan="3">
<widget class="QWidget" name="navBarWidget" native="true">
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="margin">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
......
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