Commit 81524eeb authored by Lorenz Meier's avatar Lorenz Meier

Added DSM binding support, improved mag and board rotation UI support

parent c6d28ad1
......@@ -154,7 +154,11 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
ui->graphicsView->hide();
ui->rcCalibrationButton->setCheckable(true);
ui->rcCalibrationButton->setEnabled(false);
connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
ui->spektrumPairButton->setCheckable(true);
ui->spektrumPairButton->setEnabled(false);
connect(ui->spektrumPairButton, SIGNAL(clicked(bool)), this, SLOT(toggleSpektrumPairing(bool)));
//TODO connect buttons here to save/clear actions?
UASInterface* tmpMav = UASManager::instance()->getActiveUAS();
......@@ -329,6 +333,22 @@ void QGCPX4VehicleConfig::toggleCalibrationRC(bool enabled)
}
}
void QGCPX4VehicleConfig::toggleSpektrumPairing(bool enabled)
{
if (enabled)
{
mav->getParamManager()->setPendingParam(0, "RC_DSM_BIND", (int)1);
// Do not save this parameter, just set in RAM
mav->getParamManager()->sendPendingParameters();
}
else
{
mav->getParamManager()->setPendingParam(0, "RC_DSM_BIND", (int)0);
// Do not save this parameter, just set in RAM
mav->getParamManager()->sendPendingParameters();
}
}
void QGCPX4VehicleConfig::setTrimPositions()
{
int rollMap = rcMapping[0];
......@@ -1140,6 +1160,9 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
ui->airframeMenuButton->setEnabled(true);
ui->sensorMenuButton->setEnabled(true);
ui->rcMenuButton->setEnabled(true);
ui->rcCalibrationButton->setEnabled(true);
ui->spektrumPairButton->setEnabled(true);
}
void QGCPX4VehicleConfig::resetCalibrationRC()
......
......@@ -60,6 +60,8 @@ public slots:
void stopCalibrationRC();
/** Start/stop the RC calibration routine */
void toggleCalibrationRC(bool enabled);
/** Start/stop the Spektrum pair routine */
void toggleSpektrumPairing(bool enabled);
/** Set trim positions */
void setTrimPositions();
/** Detect which channels need to be inverted */
......
......@@ -7,7 +7,7 @@
<x>0</x>
<y>0</y>
<width>1256</width>
<height>985</height>
<height>1009</height>
</rect>
</property>
<property name="sizePolicy">
......@@ -50,9 +50,25 @@
<widget class="QWidget" name="rcTab">
<layout class="QVBoxLayout" name="verticalLayout_17">
<item>
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,0" columnstretch="0,0,0,0">
<item row="2" column="1">
<widget class="QGCRadioChannelDisplay" name="yawWidget" native="true">
<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>
......@@ -67,6 +83,28 @@
</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>
......@@ -135,30 +173,8 @@
</item>
</layout>
</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="2" column="2">
<widget class="QGCRadioChannelDisplay" name="rollWidget" native="true">
<item row="1" column="1">
<widget class="QGCRadioChannelDisplay" name="yawWidget" native="true">
<property name="minimumSize">
<size>
<width>250</width>
......@@ -173,28 +189,36 @@
</property>
</widget>
</item>
<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="0" column="0">
<widget class="QPushButton" name="rcCalibrationButton">
<property name="text">
<string>Start Calibration</string>
</property>
</widget>
<layout class="QVBoxLayout" name="verticalLayout_9">
<item>
<widget class="QPushButton" name="rcCalibrationButton">
<property name="text">
<string>Start Calibration</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="spektrumPairButton">
<property name="text">
<string>Spektrum RC Pairing</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>
</layout>
</item>
</layout>
</item>
......@@ -829,8 +853,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">
......@@ -866,8 +890,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">
......@@ -917,8 +941,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">
......
......@@ -67,6 +67,18 @@ QGCPX4SensorCalibration::QGCPX4SensorCalibration(QWidget *parent) :
ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_270_YAW_135"), 23);
ui->autopilotComboBox->addItem(tr("ROTATION_PITCH_90"), 24);
ui->autopilotComboBox->addItem(tr("ROTATION_PITCH_270"), 25);
ui->autopilotComboBox->addItem(tr("ROTATION_PITCH_180_YAW_90"), 26);
ui->autopilotComboBox->addItem(tr("ROTATION_PITCH_180_YAW_270"), 27);
ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_PITCH_90"), 28);
ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_180_PITCH_90"), 29);
ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_270_PITCH_90"), 30);
ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_PITCH_180"), 31);
ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_270_PITCH_180"), 32);
ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_PITCH_270"), 33);
ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_180_PITCH_270"), 34);
ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_270_PITCH_270"), 35);
ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_PITCH_180_YAW_90"), 36);
ui->autopilotComboBox->addItem(tr("ROTATION_ROLL_90_YAW_270"), 37);
ui->magComboBox->addItem(tr("Default Orientation"), 0);
ui->magComboBox->addItem(tr("ROTATION_YAW_45"), 1);
......@@ -381,8 +393,10 @@ void QGCPX4SensorCalibration::handleTextMessage(int uasid, int compId, int sever
accelStarted = false;
// XXX use a confirmation image or something
setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
if (activeUAS)
if (activeUAS) {
activeUAS->requestParameter(0, "SENS_ACC_XOFF");
activeUAS->requestParameter(0, "SENS_BOARD_ROT");
}
}
if (text.contains("gyro calibration done")) {
......@@ -398,8 +412,10 @@ void QGCPX4SensorCalibration::handleTextMessage(int uasid, int compId, int sever
magStarted = false;
// XXX use a confirmation image or something
setInstructionImage(":/files/images/px4/calibration/accel_z-.png");
if (activeUAS)
if (activeUAS) {
activeUAS->requestParameter(0, "SENS_MAG_XOFF");
activeUAS->requestParameter(0, "SENS_EXT_MAG_ROT");
}
}
if (text.contains("accel calibration started")) {
......
......@@ -179,6 +179,12 @@ QPushButton#gyroButton, QPushButton#accelButton {
</item>
<item row="4" column="1">
<widget class="QLabel" name="gpsLabel">
<property name="minimumSize">
<size>
<width>150</width>
<height>150</height>
</size>
</property>
<property name="text">
<string/>
</property>
......
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