Browse Source

Huge step towards usability goals: Graphic vehicle configuration in a first (ugly) sketch

QGC4.4
Lorenz Meier 13 years ago
parent
commit
9d152ddc9d
  1. 50
      files/px4/quadrotor/widgets/px4_calibration.qgw
  2. 2
      files/px4/widgets/px4_calibration.qgw
  3. 8
      files/px4/widgets/px4_fw_attitude_pid_params.qgw
  4. 8
      files/px4/widgets/px4_fw_position_pid_params.qgw
  5. 62
      files/px4/widgets/px4_mc_attitude_pid_params.qgw
  6. 3
      src/uas/UAS.h
  7. 16
      src/ui/MainWindow.cc
  8. 24
      src/ui/QGCRemoteControlView.cc
  9. 298
      src/ui/QGCVehicleConfig.cc
  10. 14
      src/ui/QGCVehicleConfig.h
  11. 934
      src/ui/QGCVehicleConfig.ui

50
files/px4/quadrotor/widgets/px4_calibration.qgw

@ -1,50 +0,0 @@
[PX4%20Calibration%20Tool]
QGC_TOOL_WIDGET_ITEMS\1\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_DESCRIPTION=Reboot (only in standby)
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_BUTTONTEXT=REBOOT
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_COMMANDID=246
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM1=1
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM2=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM4=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\2\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_BUTTONTEXT=MAG
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_COMMANDID=241
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM1=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM2=1
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM4=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\3\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_DESCRIPTION=Accelerometer calibration
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_BUTTONTEXT=ACCEL
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_COMMANDID=241
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM1=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM2=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM4=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM5=1
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\4\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_BUTTONTEXT=GYRO
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_COMMANDID=241
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM1=1
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM2=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM3=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM4=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\size=4

2
files/px4/hexarotor/widgets/px4_calibration.qgw → files/px4/widgets/px4_calibration.qgw

@ -12,7 +12,7 @@ QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM5=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM6=0 QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM6=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM7=0 QGC_TOOL_WIDGET_ITEMS\1\QGC_COMMAND_BUTTON_PARAM7=0
QGC_TOOL_WIDGET_ITEMS\2\TYPE=COMMANDBUTTON QGC_TOOL_WIDGET_ITEMS\2\TYPE=COMMANDBUTTON
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_DESCRIPTION=Gyroscope calibration QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_DESCRIPTION=Magnetometer calibration
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_BUTTONTEXT=MAG QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_BUTTONTEXT=MAG
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_COMMANDID=241 QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_COMMANDID=241
QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false QGC_TOOL_WIDGET_ITEMS\2\QGC_COMMAND_BUTTON_PARAMS_VISIBLE=false

8
files/px4/widgets/px4_fw_attitude_pid_params.qgw

@ -0,0 +1,8 @@
[PX4%20Fixed%20Wing%20Attitude%20Control]
QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Roll Rate P Gain
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=FW_ROLLRATE_P
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=50
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=2
QGC_TOOL_WIDGET_ITEMS\size=1

8
files/px4/widgets/px4_fw_position_pid_params.qgw

@ -0,0 +1,8 @@
[PX4%20Fixed%20Wing%20Position%20Control]
QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Heading P Gain
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=FW_HEADING_P
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=50
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=2
QGC_TOOL_WIDGET_ITEMS\size=1

62
files/px4/widgets/px4_mc_attitude_pid_params.qgw

@ -0,0 +1,62 @@
[PX4%20Multirotor%20Attitude%20Control]
QGC_TOOL_WIDGET_ITEMS\1\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_DESCRIPTION=Attitude P Gain
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_PARAMID=MC_ATT_P
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_COMPONENTID=50
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\1\QGC_PARAM_SLIDER_MAX=1.5
QGC_TOOL_WIDGET_ITEMS\2\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_DESCRIPTION=Attitude I Gain
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_PARAMID=MC_ATT_I
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_COMPONENTID=50
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\2\QGC_PARAM_SLIDER_MAX=1
QGC_TOOL_WIDGET_ITEMS\3\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_DESCRIPTION=Attitude D Gain
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_PARAMID=MC_ATT_D
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_COMPONENTID=50
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\3\QGC_PARAM_SLIDER_MAX=1
QGC_TOOL_WIDGET_ITEMS\4\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_DESCRIPTION=Attitude Anti-Windup
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_PARAMID=MC_ATT_AWU
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_COMPONENTID=50
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\4\QGC_PARAM_SLIDER_MAX=1
QGC_TOOL_WIDGET_ITEMS\5\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_DESCRIPTION=Attitude Output Limit
QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_PARAMID=MC_ATT_LIM
QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_COMPONENTID=50
QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\5\QGC_PARAM_SLIDER_MAX=3
QGC_TOOL_WIDGET_ITEMS\6\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_DESCRIPTION=Heading / Yaw P Gain
QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_PARAMID=MC_YAWPOS_P
QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_COMPONENTID=50
QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\6\QGC_PARAM_SLIDER_MAX=1.2
QGC_TOOL_WIDGET_ITEMS\7\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_DESCRIPTION=Heading / Yaw D Gain
QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_PARAMID=MC_YAWPOS_D
QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_COMPONENTID=50
QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\7\QGC_PARAM_SLIDER_MAX=1
QGC_TOOL_WIDGET_ITEMS\8\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_DESCRIPTION=Roll / Pitch Rate P Gain
QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_PARAMID=MC_ATTRATE_P
QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_COMPONENTID=50
QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\8\QGC_PARAM_SLIDER_MAX=1.5
QGC_TOOL_WIDGET_ITEMS\9\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_DESCRIPTION=Roll / Pitch Rate D Gain
QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_PARAMID=MC_ATTRATE_D
QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_COMPONENTID=50
QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\9\QGC_PARAM_SLIDER_MAX=0.3
QGC_TOOL_WIDGET_ITEMS\10\TYPE=SLIDER
QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_DESCRIPTION=Yaw Rate P Gain
QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_PARAMID=MC_YAWRATE_P
QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_COMPONENTID=50
QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_MIN=0
QGC_TOOL_WIDGET_ITEMS\10\QGC_PARAM_SLIDER_MAX=1
QGC_TOOL_WIDGET_ITEMS\size=10

3
src/uas/UAS.h

@ -478,6 +478,9 @@ public:
case MAV_AUTOPILOT_FP: case MAV_AUTOPILOT_FP:
return "FP"; return "FP";
break; break;
case MAV_AUTOPILOT_PX4:
return "PX4";
break;
default: default:
return ""; return "";
break; break;

16
src/ui/MainWindow.cc

@ -564,11 +564,11 @@ void MainWindow::buildCommonWidgets()
addCentralWidget(hudWidget, tr("Head Up Display")); addCentralWidget(hudWidget, tr("Head Up Display"));
} }
// if (!configWidget) if (!configWidget)
// { {
// configWidget = new QGCVehicleConfig(this); configWidget = new QGCVehicleConfig(this);
// addCentralWidget(configWidget, tr("Vehicle Configuration")); addCentralWidget(configWidget, tr("Vehicle Configuration"));
// } }
if (!dataplotWidget) if (!dataplotWidget)
{ {
@ -724,10 +724,14 @@ void MainWindow::loadCustomWidget(const QString& fileName, bool singleinstance)
void MainWindow::loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType) void MainWindow::loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType)
{ {
QString defaultsDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/" + systemType.toLower() + "/widgets/"; QString defaultsDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/widgets/";
QString platformDir = qApp->applicationDirPath() + "/files/" + autopilotType.toLower() + "/" + systemType.toLower() + "/widgets/";
QDir widgets(defaultsDir); QDir widgets(defaultsDir);
QStringList files = widgets.entryList(); QStringList files = widgets.entryList();
QDir platformWidgets(platformDir);
files.append(platformWidgets.entryList());
if (files.count() == 0) if (files.count() == 0)
{ {
qDebug() << "No default custom widgets for system " << systemType << "autopilot" << autopilotType << " found"; qDebug() << "No default custom widgets for system " << systemType << "autopilot" << autopilotType << " found";

24
src/ui/QGCRemoteControlView.cc

@ -55,13 +55,13 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) :
this->setVisible(false); this->setVisible(false);
//setVisible(false); //setVisible(false);
calibrate = new QPushButton(tr("Calibrate"), this); // calibrate = new QPushButton(tr("Calibrate"), this);
QHBoxLayout *calibrateButtonLayout = new QHBoxLayout(); // QHBoxLayout *calibrateButtonLayout = new QHBoxLayout();
calibrateButtonLayout->addWidget(calibrate, 0, Qt::AlignHCenter); // calibrateButtonLayout->addWidget(calibrate, 0, Qt::AlignHCenter);
layout->addItem(calibrateButtonLayout, 3, 0, 1, 2); // layout->addItem(calibrateButtonLayout, 3, 0, 1, 2);
calibrationWindow = new RadioCalibrationWindow(this); // calibrationWindow = new RadioCalibrationWindow(this);
connect(calibrate, SIGNAL(clicked()), calibrationWindow, SLOT(show())); // connect(calibrate, SIGNAL(clicked()), calibrationWindow, SLOT(show()));
connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(setUASId(int))); connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(setUASId(int)));
@ -91,8 +91,8 @@ void QGCRemoteControlView::setUASId(int id)
// The UAS exists, disconnect any existing connections // The UAS exists, disconnect any existing connections
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float,float)), this, SLOT(setChannel(int,float,float))); disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
disconnect(uas, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float))); disconnect(uas, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer<RadioCalibrationData>&)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&))); //disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer<RadioCalibrationData>&)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float))); //disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float)));
disconnect(uas, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float))); disconnect(uas, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float)));
} }
} }
@ -124,15 +124,15 @@ void QGCRemoteControlView::setUASId(int id)
{ {
// New UAS exists, connect // New UAS exists, connect
nameLabel->setText(QString("RC Input of %1").arg(newUAS->getUASName())); nameLabel->setText(QString("RC Input of %1").arg(newUAS->getUASName()));
calibrationWindow->setUASId(id); //calibrationWindow->setUASId(id);
connect(newUAS, SIGNAL(radioCalibrationReceived(const QPointer<RadioCalibrationData>&)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&))); //connect(newUAS, SIGNAL(radioCalibrationReceived(const QPointer<RadioCalibrationData>&)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
connect(newUAS, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float))); connect(newUAS, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float))); connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float))); connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float)));
// only connect raw channels to calibration window widget // only connect raw channels to calibration window widget
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float))); //connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float)));
} }
} }
@ -178,7 +178,7 @@ void QGCRemoteControlView::setRemoteRSSI(float rssiNormalized)
void QGCRemoteControlView::appendChannelWidget(int channelId) void QGCRemoteControlView::appendChannelWidget(int channelId)
{ {
// Create new layout // Create new layout
QHBoxLayout* layout = new QHBoxLayout(this); QHBoxLayout* layout = new QHBoxLayout();
// Add content // Add content
layout->addWidget(new QLabel(QString("Channel %1").arg(channelId + 1), this)); layout->addWidget(new QLabel(QString("Channel %1").arg(channelId + 1), this));
QLabel* raw = new QLabel(this); QLabel* raw = new QLabel(this);

298
src/ui/QGCVehicleConfig.cc

@ -5,12 +5,22 @@
#include "QGCVehicleConfig.h" #include "QGCVehicleConfig.h"
#include "UASManager.h" #include "UASManager.h"
#include "QGC.h" #include "QGC.h"
#include "QGCToolWidget.h"
#include "ui_QGCVehicleConfig.h" #include "ui_QGCVehicleConfig.h"
QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) : QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
QWidget(parent), QWidget(parent),
mav(NULL), mav(NULL),
changed(true), changed(true),
rc_mode(RC_MODE_2),
rcRoll(0.0f),
rcPitch(0.0f),
rcYaw(0.0f),
rcThrottle(0.0f),
rcMode(0.0f),
rcAux1(0.0f),
rcAux2(0.0f),
rcAux3(0.0f),
ui(new Ui::QGCVehicleConfig) ui(new Ui::QGCVehicleConfig)
{ {
setObjectName("QGC_VEHICLECONFIG"); setObjectName("QGC_VEHICLECONFIG");
@ -19,8 +29,11 @@ QGCVehicleConfig::QGCVehicleConfig(QWidget *parent) :
requestCalibrationRC(); requestCalibrationRC();
if (mav) mav->requestParameter(0, "RC_TYPE"); if (mav) mav->requestParameter(0, "RC_TYPE");
ui->rcModeComboBox->setCurrentIndex((int)rc_mode - 1);
connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool))); connect(ui->rcCalibrationButton, SIGNAL(clicked(bool)), this, SLOT(toggleCalibrationRC(bool)));
connect(ui->storeButton, SIGNAL(clicked()), this, SLOT(writeParameters())); connect(ui->storeButton, SIGNAL(clicked()), this, SLOT(writeParameters()));
connect(ui->rcModeComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setRCModeIndex(int)));
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
@ -41,6 +54,14 @@ QGCVehicleConfig::~QGCVehicleConfig()
delete ui; delete ui;
} }
void QGCVehicleConfig::setRCModeIndex(int newRcMode)
{
if (newRcMode > 0 && newRcMode < 5)
{
rc_mode = (enum RC_MODE) (newRcMode+1);
changed = true;
}
}
void QGCVehicleConfig::toggleCalibrationRC(bool enabled) void QGCVehicleConfig::toggleCalibrationRC(bool enabled)
{ {
@ -57,12 +78,14 @@ void QGCVehicleConfig::toggleCalibrationRC(bool enabled)
void QGCVehicleConfig::startCalibrationRC() void QGCVehicleConfig::startCalibrationRC()
{ {
ui->rcTypeComboBox->setEnabled(false); ui->rcTypeComboBox->setEnabled(false);
ui->rcCalibrationButton->setText(tr("Stop RC Calibration"));
resetCalibrationRC(); resetCalibrationRC();
} }
void QGCVehicleConfig::stopCalibrationRC() void QGCVehicleConfig::stopCalibrationRC()
{ {
ui->rcTypeComboBox->setEnabled(true); ui->rcTypeComboBox->setEnabled(true);
ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
} }
void QGCVehicleConfig::setActiveUAS(UASInterface* active) void QGCVehicleConfig::setActiveUAS(UASInterface* active)
@ -77,15 +100,69 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active)
SLOT(remoteControlChannelRawChanged(int,float))); SLOT(remoteControlChannelRawChanged(int,float)));
disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
SLOT(parameterChanged(int,int,QString,QVariant))); SLOT(parameterChanged(int,int,QString,QVariant)));
resetCalibrationRC();
foreach (QGCToolWidget* tool, toolWidgets)
{
delete tool;
}
} }
// Reset current state
resetCalibrationRC();
// Connect new system // Connect new system
mav = active; mav = active;
connect(active, SIGNAL(remoteControlChannelRawChanged(int,float)), this, connect(active, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
SLOT(remoteControlChannelRawChanged(int,float))); SLOT(remoteControlChannelRawChanged(int,float)));
connect(active, SIGNAL(parameterChanged(int,int,QString,QVariant)), this, connect(active, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
SLOT(parameterChanged(int,int,QString,QVariant))); SLOT(parameterChanged(int,int,QString,QVariant)));
mav->requestParameters();
QString defaultsDir = qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower() + "/widgets/";
QGCToolWidget* tool;
// Load calibration
tool = new QGCToolWidget("", this);
if (tool->loadSettings(defaultsDir + "px4_calibration.qgw", false))
{
toolWidgets.append(tool);
ui->sensorLayout->addWidget(tool);
}
// Load multirotor attitude pid
tool = new QGCToolWidget("", this);
if (tool->loadSettings(defaultsDir + "px4_mc_attitude_pid_params.qgw", false))
{
toolWidgets.append(tool);
ui->multiRotorAttitudeLayout->addWidget(tool);
}
// Load multirotor position pid
tool = new QGCToolWidget("", this);
if (tool->loadSettings(defaultsDir + "px4_mc_position_pid_params.qgw", false))
{
toolWidgets.append(tool);
ui->multiRotorPositionLayout->addWidget(tool);
}
// Load fixed wing attitude pid
tool = new QGCToolWidget("", this);
if (tool->loadSettings(defaultsDir + "px4_fw_attitude_pid_params.qgw", false))
{
toolWidgets.append(tool);
ui->fixedWingAttitudeLayout->addWidget(tool);
}
// Load fixed wing position pid
tool = new QGCToolWidget("", this);
if (tool->loadSettings(defaultsDir + "px4_fw_position_pid_params.qgw", false))
{
toolWidgets.append(tool);
ui->fixedWingPositionLayout->addWidget(tool);
}
updateStatus(QString("Reading from system %1").arg(mav->getUASName()));
} }
void QGCVehicleConfig::resetCalibrationRC() void QGCVehicleConfig::resetCalibrationRC()
@ -177,6 +254,16 @@ void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val)
if (chan < 0 || static_cast<unsigned int>(chan) >= chanMax) if (chan < 0 || static_cast<unsigned int>(chan) >= chanMax)
return; return;
if (val < rcMin[chan])
{
rcMin[chan] = val;
}
if (val > rcMax[chan])
{
rcMax[chan] = val;
}
if (chan == rcMapping[0]) if (chan == rcMapping[0])
{ {
// ROLL // ROLL
@ -252,16 +339,19 @@ void QGCVehicleConfig::remoteControlChannelRawChanged(int chan, float val)
{ {
// AUX1 // AUX1
rcAux1 = val; rcAux1 = val;
rcValue[5] = val;
} }
else if (chan == rcMapping[6]) else if (chan == rcMapping[6])
{ {
// AUX2 // AUX2
rcAux2 = val; rcAux2 = val;
rcValue[6] = val;
} }
else if (chan == rcMapping[7]) else if (chan == rcMapping[7])
{ {
// AUX3 // AUX3
rcAux3 = val; rcAux3 = val;
rcValue[7] = val;
} }
changed = true; changed = true;
@ -273,6 +363,91 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete
{ {
Q_UNUSED(uas); Q_UNUSED(uas);
Q_UNUSED(component); Q_UNUSED(component);
// Channel calibration values
QRegExp minTpl("RC?_MIN");
minTpl.setPatternSyntax(QRegExp::Wildcard);
QRegExp maxTpl("RC?_MAX");
maxTpl.setPatternSyntax(QRegExp::Wildcard);
QRegExp trimTpl("RC?_TRIM");
trimTpl.setPatternSyntax(QRegExp::Wildcard);
QRegExp revTpl("RC?_REV");
revTpl.setPatternSyntax(QRegExp::Wildcard);
// Do not write the RC type, as these values depend on this
// active onboard parameter
if (minTpl.exactMatch(parameterName)) {
bool ok;
unsigned int index = parameterName.mid(2, 1).toInt(&ok);
if (ok && (index > 0) && (index < chanMax))
{
rcMin[index] = value.toInt();
}
}
if (maxTpl.exactMatch(parameterName)) {
bool ok;
unsigned int index = parameterName.mid(2, 1).toInt(&ok);
if (ok && (index > 0) && (index < chanMax))
{
rcMax[index] = value.toInt();
}
}
if (trimTpl.exactMatch(parameterName)) {
bool ok;
unsigned int index = parameterName.mid(2, 1).toInt(&ok);
if (ok && (index > 0) && (index < chanMax))
{
rcTrim[index] = value.toInt();
}
}
if (revTpl.exactMatch(parameterName)) {
bool ok;
unsigned int index = parameterName.mid(2, 1).toInt(&ok);
if (ok && (index > 0) && (index < chanMax))
{
rcRev[index] = (value.toInt() == -1) ? true : false;
unsigned int mapindex = rcMapping[index];
switch (mapindex)
{
case 0:
ui->invertCheckBox->setChecked(rcRev[index]);
break;
case 1:
ui->invertCheckBox_2->setChecked(rcRev[index]);
break;
case 2:
ui->invertCheckBox_3->setChecked(rcRev[index]);
break;
case 3:
ui->invertCheckBox_4->setChecked(rcRev[index]);
break;
case 4:
ui->invertCheckBox_5->setChecked(rcRev[index]);
break;
case 5:
ui->invertCheckBox_6->setChecked(rcRev[index]);
break;
case 6:
ui->invertCheckBox_7->setChecked(rcRev[index]);
break;
case 7:
ui->invertCheckBox_8->setChecked(rcRev[index]);
break;
}
}
}
// mav->setParameter(0, trimTpl.arg(i), rcTrim[i]);
// mav->setParameter(0, maxTpl.arg(i), rcMax[i]);
// mav->setParameter(0, revTpl.arg(i), (rcRev[i]) ? -1 : 1);
// }
if (rcTypeUpdateRequested > 0 && parameterName == QString("RC_TYPE")) if (rcTypeUpdateRequested > 0 && parameterName == QString("RC_TYPE"))
{ {
rcTypeUpdateRequested = 0; rcTypeUpdateRequested = 0;
@ -281,6 +456,82 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete
// Request all other parameters as well // Request all other parameters as well
requestCalibrationRC(); requestCalibrationRC();
} }
// Order is: roll, pitch, yaw, throttle, mode sw, aux 1-3
if (parameterName.contains("RC_MAP_ROLL")) {
rcMapping[0] = value.toInt();
ui->rollSpinBox->setValue(rcMapping[0]);
}
if (parameterName.contains("RC_MAP_PITCH")) {
rcMapping[1] = value.toInt();
ui->pitchSpinBox->setValue(rcMapping[1]);
}
if (parameterName.contains("RC_MAP_YAW")) {
rcMapping[2] = value.toInt();
ui->yawSpinBox->setValue(rcMapping[2]);
}
if (parameterName.contains("RC_MAP_THROTTLE")) {
rcMapping[3] = value.toInt();
ui->throttleSpinBox->setValue(rcMapping[3]);
}
if (parameterName.contains("RC_MAP_MODE_SW")) {
rcMapping[4] = value.toInt();
ui->modeSpinBox->setValue(rcMapping[4]);
}
if (parameterName.contains("RC_MAP_AUX1")) {
rcMapping[5] = value.toInt();
ui->aux1SpinBox->setValue(rcMapping[5]);
}
if (parameterName.contains("RC_MAP_AUX2")) {
rcMapping[6] = value.toInt();
ui->aux1SpinBox->setValue(rcMapping[6]);
}
if (parameterName.contains("RC_MAP_AUX3")) {
rcMapping[7] = value.toInt();
ui->aux1SpinBox->setValue(rcMapping[7]);
}
// Scaling
if (parameterName.contains("RC_SCALE_ROLL")) {
rcScaling[0] = value.toInt();
}
if (parameterName.contains("RC_SCALE_PITCH")) {
rcScaling[1] = value.toInt();
}
if (parameterName.contains("RC_SCALE_YAW")) {
rcScaling[2] = value.toInt();
}
if (parameterName.contains("RC_SCALE_THROTTLE")) {
rcScaling[3] = value.toInt();
}
if (parameterName.contains("RC_SCALE_MODE_SW")) {
rcScaling[4] = value.toInt();
}
if (parameterName.contains("RC_SCALE_AUX1")) {
rcScaling[5] = value.toInt();
}
if (parameterName.contains("RC_SCALE_AUX2")) {
rcScaling[6] = value.toInt();
}
if (parameterName.contains("RC_SCALE_AUX3")) {
rcScaling[7] = value.toInt();
}
} }
void QGCVehicleConfig::updateStatus(const QString& str) void QGCVehicleConfig::updateStatus(const QString& str)
@ -321,10 +572,47 @@ void QGCVehicleConfig::updateView()
{ {
if (changed) if (changed)
{ {
ui->rollSlider->setValue(rcValue[0]); if (rc_mode == RC_MODE_1)
ui->pitchSlider->setValue(rcValue[1]); {
ui->yawSlider->setValue(rcValue[2]); ui->rollSlider->setValue(rcRoll);
ui->throttleSlider->setValue(rcValue[3]); ui->pitchSlider->setValue(rcThrottle);
ui->yawSlider->setValue(rcYaw);
ui->throttleSlider->setValue(rcPitch);
}
else if (rc_mode == RC_MODE_2)
{
ui->rollSlider->setValue(rcRoll);
ui->pitchSlider->setValue(rcPitch);
ui->yawSlider->setValue(rcYaw);
ui->throttleSlider->setValue(rcThrottle);
}
else if (rc_mode == RC_MODE_3)
{
ui->rollSlider->setValue(rcYaw);
ui->pitchSlider->setValue(rcThrottle);
ui->yawSlider->setValue(rcRoll);
ui->throttleSlider->setValue(rcPitch);
}
else if (rc_mode == RC_MODE_4)
{
ui->rollSlider->setValue(rcYaw);
ui->pitchSlider->setValue(rcPitch);
ui->yawSlider->setValue(rcRoll);
ui->throttleSlider->setValue(rcThrottle);
}
ui->chanLabel->setText(QString("%1/%2").arg(rcValue[0]).arg(rcRoll));
ui->chanLabel_2->setText(QString("%1/%2").arg(rcValue[1]).arg(rcPitch));
ui->chanLabel_3->setText(QString("%1/%2").arg(rcValue[2]).arg(rcYaw));
ui->chanLabel_4->setText(QString("%1/%2").arg(rcValue[3]).arg(rcThrottle));
ui->modeSwitchSlider->setValue(rcMode);
ui->chanLabel_5->setText(QString("%1/%2").arg(rcValue[4]).arg(rcMode));
ui->aux1Slider->setValue(rcAux1);
ui->chanLabel_6->setText(QString("%1/%2").arg(rcValue[5]).arg(rcAux1));
ui->aux2Slider->setValue(rcAux2);
ui->chanLabel_7->setText(QString("%1/%2").arg(rcValue[6]).arg(rcAux2));
ui->aux3Slider->setValue(rcAux3);
ui->chanLabel_8->setText(QString("%1/%2").arg(rcValue[7]).arg(rcAux3));
changed = false; changed = false;
} }
} }

14
src/ui/QGCVehicleConfig.h

@ -3,7 +3,9 @@
#include <QWidget> #include <QWidget>
#include <QTimer> #include <QTimer>
#include <QList>
#include "QGCToolWidget.h"
#include "UASInterface.h" #include "UASInterface.h"
namespace Ui { namespace Ui {
@ -18,6 +20,13 @@ public:
explicit QGCVehicleConfig(QWidget *parent = 0); explicit QGCVehicleConfig(QWidget *parent = 0);
~QGCVehicleConfig(); ~QGCVehicleConfig();
enum RC_MODE {
RC_MODE_1 = 1,
RC_MODE_2 = 2,
RC_MODE_3 = 3,
RC_MODE_4 = 4
};
public slots: public slots:
/** Set the MAV currently being calibrated */ /** Set the MAV currently being calibrated */
void setActiveUAS(UASInterface* active); void setActiveUAS(UASInterface* active);
@ -28,6 +37,8 @@ public slots:
void stopCalibrationRC(); void stopCalibrationRC();
/** Start/stop the RC calibration routine */ /** Start/stop the RC calibration routine */
void toggleCalibrationRC(bool enabled); void toggleCalibrationRC(bool enabled);
/** Change the mode setting of the control inputs */
void setRCModeIndex(int newRcMode);
/** Render the data updated */ /** Render the data updated */
void updateView(); void updateView();
@ -60,6 +71,7 @@ protected:
int rcMax[chanMax]; ///< Maximum values int rcMax[chanMax]; ///< Maximum values
int rcTrim[chanMax]; ///< Zero-position (center for roll/pitch/yaw, 0 throttle for throttle) int rcTrim[chanMax]; ///< Zero-position (center for roll/pitch/yaw, 0 throttle for throttle)
int rcMapping[chanMax]; ///< PWM to function mappings int rcMapping[chanMax]; ///< PWM to function mappings
float rcScaling[chanMax]; ///< Scaling of channel input to control commands
bool rcRev[chanMax]; ///< Channel reverse bool rcRev[chanMax]; ///< Channel reverse
int rcValue[chanMax]; ///< Last values int rcValue[chanMax]; ///< Last values
float rcRoll; ///< PPM input channel used as roll control input float rcRoll; ///< PPM input channel used as roll control input
@ -73,6 +85,8 @@ protected:
bool rcCalChanged; ///< Set if the calibration changes (and needs to be written) bool rcCalChanged; ///< Set if the calibration changes (and needs to be written)
bool changed; ///< Set if any of the input data changed bool changed; ///< Set if any of the input data changed
QTimer updateTimer; ///< Controls update intervals QTimer updateTimer; ///< Controls update intervals
enum RC_MODE rc_mode; ///< Mode of the remote control, according to usual convention
QList<QGCToolWidget*> toolWidgets; ///< Configurable widgets
private: private:
Ui::QGCVehicleConfig *ui; Ui::QGCVehicleConfig *ui;

934
src/ui/QGCVehicleConfig.ui

File diff suppressed because it is too large Load Diff
Loading…
Cancel
Save