Commit 31a118ce authored by Michael Carpenter's avatar Michael Carpenter

First round of fixes per Bill's git commit comments

parent 8a8e6339
......@@ -1527,7 +1527,6 @@ void MainWindow::connectCommonActions()
connect(ui.actionEngineersView, SIGNAL(triggered()), this, SLOT(loadEngineerView()));
connect(ui.actionMissionView, SIGNAL(triggered()), this, SLOT(loadOperatorView()));
connect(ui.actionUnconnectedView, SIGNAL(triggered()), this, SLOT(loadUnconnectedView()));
//connect(ui.actionConfiguration_2,SIGNAL(triggered()),this,SLOT(loadConfigurationView()));
connect(ui.actionHardwareConfig,SIGNAL(triggered()),this,SLOT(loadHardwareConfigView()));
connect(ui.actionSoftwareConfig,SIGNAL(triggered()),this,SLOT(loadSoftwareConfigView()));
......
......@@ -30,7 +30,6 @@ This file is part of the QGROUNDCONTROL project
#ifndef _MAINWINDOW_H_
#define _MAINWINDOW_H_
#include <QtGui/QMainWindow>
#include <QStatusBar>
#include <QStackedWidget>
......
#include <QMessageBox>
#include "AP2ConfigWidget.h"
AP2ConfigWidget::AP2ConfigWidget(QWidget *parent) : QWidget(parent)
......@@ -8,11 +9,12 @@ AP2ConfigWidget::AP2ConfigWidget(QWidget *parent) : QWidget(parent)
}
void AP2ConfigWidget::activeUASSet(UASInterface *uas)
{
if (!uas) return;
if (m_uas)
{
disconnect(m_uas,SIGNAL(parameterChanged(int,int,QString,QVariant)),this,SLOT(parameterChanged(int,int,QString,QVariant)));
m_uas = 0;
}
if (!uas) return;
m_uas = uas;
connect(m_uas,SIGNAL(parameterChanged(int,int,QString,QVariant)),this,SLOT(parameterChanged(int,int,QString,QVariant)));
}
......@@ -21,3 +23,7 @@ void AP2ConfigWidget::parameterChanged(int uas, int component, QString parameter
{
}
void AP2ConfigWidget::showNullMAVErrorMessageBox()
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
}
......@@ -11,6 +11,7 @@ public:
explicit AP2ConfigWidget(QWidget *parent = 0);
protected:
UASInterface *m_uas;
void showNullMAVErrorMessageBox();
signals:
public slots:
......
#include "AccelCalibrationConfig.h"
AccelCalibrationConfig::AccelCalibrationConfig(QWidget *parent) : QWidget(parent)
AccelCalibrationConfig::AccelCalibrationConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
m_uas=0;
ui.setupUi(this);
......@@ -9,7 +9,7 @@ AccelCalibrationConfig::AccelCalibrationConfig(QWidget *parent) : QWidget(parent
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
activeUASSet(UASManager::instance()->getActiveUAS());
accelAckCount=0;
m_accelAckCount=0;
}
AccelCalibrationConfig::~AccelCalibrationConfig()
......@@ -17,42 +17,48 @@ AccelCalibrationConfig::~AccelCalibrationConfig()
}
void AccelCalibrationConfig::activeUASSet(UASInterface *uas)
{
if (!uas)
if (m_uas)
{
return;
disconnect(m_uas,SIGNAL(textMessageReceived(int,int,int,QString)),this,SLOT(uasTextMessageReceived(int,int,int,QString)));
}
if (m_uas)
AP2ConfigWidget::activeUASSet(uas);
if (!uas)
{
return;
}
m_uas = uas;
connect(m_uas,SIGNAL(textMessageReceived(int,int,int,QString)),this,SLOT(uasTextMessageReceived(int,int,int,QString)));
}
void AccelCalibrationConfig::calibrateButtonClicked()
{
if (accelAckCount == 0)
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
if (m_accelAckCount == 0)
{
MAV_CMD command = MAV_CMD_PREFLIGHT_CALIBRATION;
int confirm = 0;
float param1 = 0;
float param2 = 0;
float param3 = 0;
float param4 = 0;
float param5 = 1;
float param6 = 0;
float param7 = 0;
float param1 = 0.0;
float param2 = 0.0;
float param3 = 0.0;
float param4 = 0.0;
float param5 = 1.0;
float param6 = 0.0;
float param7 = 0.0;
int component = 1;
m_uas->executeCommand(command, confirm, param1, param2, param3, param4, param5, param6, param7, component);
}
else if (accelAckCount <= 5)
else if (m_accelAckCount <= 5)
{
m_uas->executeCommandAck(accelAckCount++,true);
m_uas->executeCommandAck(m_accelAckCount++,true);
}
else
{
m_uas->executeCommandAck(accelAckCount++,true);
m_uas->executeCommandAck(m_accelAckCount++,true);
ui.calibrateAccelButton->setText("Calibrate\nAccelerometer");
//accelAckCount = 0;
}
}
......@@ -63,24 +69,24 @@ void AccelCalibrationConfig::uasTextMessageReceived(int uasid, int componentid,
if (severity == 5)
{
//This is a calibration instruction
if (accelAckCount == 0)
if (m_accelAckCount == 0)
{
//Calibration Sucessful\r"
ui.calibrateAccelButton->setText("Any\nKey");
accelAckCount++;
m_accelAckCount++;
}
if (accelAckCount == 7)
if (m_accelAckCount == 7)
{
//All finished
//ui.outputLabel->setText(ui.outputLabel->text() + "\n" + text);
ui.outputLabel->setText(text);
accelAckCount++;
m_accelAckCount++;
}
if (accelAckCount == 8)
if (m_accelAckCount == 8)
{
if (text.contains("Calibration") && text.contains("successful"))
{
accelAckCount = 0;
m_accelAckCount = 0;
}
ui.outputLabel->setText(ui.outputLabel->text() + "\n" + text);
}
......
......@@ -5,7 +5,9 @@
#include "ui_AccelCalibrationConfig.h"
#include "UASManager.h"
#include "UASInterface.h"
class AccelCalibrationConfig : public QWidget
#include "AP2ConfigWidget.h"
class AccelCalibrationConfig : public AP2ConfigWidget
{
Q_OBJECT
......@@ -17,7 +19,7 @@ private slots:
void calibrateButtonClicked();
void uasTextMessageReceived(int uasid, int componentid, int severity, QString text);
private:
int accelAckCount;
int m_accelAckCount;
Ui::AccelCalibrationConfig ui;
UASInterface *m_uas;
};
......
......@@ -7,8 +7,6 @@ AdvParameterList::AdvParameterList(QWidget *parent) : AP2ConfigWidget(parent)
ui.tableWidget->setColumnCount(4);
ui.tableWidget->horizontalHeader()->hide();
ui.tableWidget->verticalHeader()->hide();
//ui.tableWidget->setHorizontalHeader(0);
//ui.tableWidget->setVerticalHeader(0);
ui.tableWidget->setColumnWidth(0,200);
ui.tableWidget->setColumnWidth(1,100);
ui.tableWidget->setColumnWidth(2,200);
......@@ -21,19 +19,19 @@ AdvParameterList::~AdvParameterList()
}
void AdvParameterList::setParameterMetaData(QString name,QString humanname,QString description)
{
paramToNameMap[name] = humanname;
paramToDescriptionMap[name] = description;
m_paramToNameMap[name] = humanname;
m_paramToDescriptionMap[name] = description;
}
void AdvParameterList::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (!paramValueMap.contains(parameterName))
if (!m_paramValueMap.contains(parameterName))
{
ui.tableWidget->setRowCount(ui.tableWidget->rowCount()+1);
if (paramToNameMap.contains(parameterName))
if (m_paramToNameMap.contains(parameterName))
{
ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,0,new QTableWidgetItem(paramToNameMap[parameterName]));
ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,0,new QTableWidgetItem(m_paramToNameMap[parameterName]));
}
else
{
......@@ -41,15 +39,15 @@ void AdvParameterList::parameterChanged(int uas, int component, QString paramete
}
ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,1,new QTableWidgetItem(QString::number(value.toFloat(),'f',2)));
ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,2,new QTableWidgetItem(parameterName));
if (paramToDescriptionMap.contains(parameterName))
if (m_paramToDescriptionMap.contains(parameterName))
{
ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,3,new QTableWidgetItem(paramToDescriptionMap[parameterName]));
ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,3,new QTableWidgetItem(m_paramToDescriptionMap[parameterName]));
}
else
{
ui.tableWidget->setItem(ui.tableWidget->rowCount()-1,3,new QTableWidgetItem("Unknown"));
}
paramValueMap[parameterName] = ui.tableWidget->item(ui.tableWidget->rowCount()-1,1);
m_paramValueMap[parameterName] = ui.tableWidget->item(ui.tableWidget->rowCount()-1,1);
}
paramValueMap[parameterName]->setText(QString::number(value.toFloat(),'f',2));
m_paramValueMap[parameterName]->setText(QString::number(value.toFloat(),'f',2));
}
......@@ -16,9 +16,9 @@ public:
private slots:
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
private:
QMap<QString,QTableWidgetItem*> paramValueMap;
QMap<QString,QString> paramToNameMap;
QMap<QString,QString> paramToDescriptionMap;
QMap<QString,QTableWidgetItem*> m_paramValueMap;
QMap<QString,QString> m_paramToNameMap;
QMap<QString,QString> m_paramToDescriptionMap;
Ui::AdvParameterList ui;
};
......
......@@ -12,7 +12,7 @@ AdvancedParamConfig::~AdvancedParamConfig()
void AdvancedParamConfig::addRange(QString title,QString description,QString param,double min,double max)
{
ParamWidget *widget = new ParamWidget(ui.scrollAreaWidgetContents);
paramToWidgetMap[param] = widget;
m_paramToWidgetMap[param] = widget;
widget->setupDouble(title + "(" + param + ")",description,0,min,max);
ui.verticalLayout->addWidget(widget);
widget->show();
......@@ -21,15 +21,15 @@ void AdvancedParamConfig::addRange(QString title,QString description,QString par
void AdvancedParamConfig::addCombo(QString title,QString description,QString param,QList<QPair<int,QString> > valuelist)
{
ParamWidget *widget = new ParamWidget(ui.scrollAreaWidgetContents);
paramToWidgetMap[param] = widget;
m_paramToWidgetMap[param] = widget;
widget->setupCombo(title + "(" + param + ")",description,valuelist);
ui.verticalLayout->addWidget(widget);
widget->show();
}
void AdvancedParamConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (paramToWidgetMap.contains(parameterName))
if (m_paramToWidgetMap.contains(parameterName))
{
paramToWidgetMap[parameterName]->setValue(value.toDouble());
m_paramToWidgetMap[parameterName]->setValue(value.toDouble());
}
}
......@@ -17,7 +17,7 @@ public:
private slots:
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
private:
QMap<QString,ParamWidget*> paramToWidgetMap;
QMap<QString,ParamWidget*> m_paramToWidgetMap;
Ui::AdvancedParamConfig ui;
};
......
......@@ -51,7 +51,7 @@ void AirspeedConfig::useCheckBoxClicked(bool checked)
{
if (!m_uas)
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
showNullMAVErrorMessageBox();
return;
}
if (checked)
......@@ -68,7 +68,7 @@ void AirspeedConfig::enableCheckBoxClicked(bool checked)
{
if (!m_uas)
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
showNullMAVErrorMessageBox();
return;
}
if (checked)
......
......@@ -62,73 +62,73 @@ ApmHardwareConfig::ApmHardwareConfig(QWidget *parent) : QWidget(parent)
QWidget *widget = new QWidget(this);
ui.stackedWidget->addWidget(widget); //Firmware placeholder.
buttonToConfigWidgetMap[ui.firmwareButton] = widget;
m_buttonToConfigWidgetMap[ui.firmwareButton] = widget;
connect(ui.firmwareButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
frameConfig = new FrameTypeConfig(this);
ui.stackedWidget->addWidget(frameConfig);
buttonToConfigWidgetMap[ui.frameTypeButton] = frameConfig;
m_frameConfig = new FrameTypeConfig(this);
ui.stackedWidget->addWidget(m_frameConfig);
m_buttonToConfigWidgetMap[ui.frameTypeButton] = m_frameConfig;
connect(ui.frameTypeButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
compassConfig = new CompassConfig(this);
ui.stackedWidget->addWidget(compassConfig);
buttonToConfigWidgetMap[ui.compassButton] = compassConfig;
m_compassConfig = new CompassConfig(this);
ui.stackedWidget->addWidget(m_compassConfig);
m_buttonToConfigWidgetMap[ui.compassButton] = m_compassConfig;
connect(ui.compassButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
accelConfig = new AccelCalibrationConfig(this);
ui.stackedWidget->addWidget(accelConfig);
buttonToConfigWidgetMap[ui.accelCalibrateButton] = accelConfig;
m_accelConfig = new AccelCalibrationConfig(this);
ui.stackedWidget->addWidget(m_accelConfig);
m_buttonToConfigWidgetMap[ui.accelCalibrateButton] = m_accelConfig;
connect(ui.accelCalibrateButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
planeLevel = new ApmPlaneLevel(this);
ui.stackedWidget->addWidget(planeLevel);
buttonToConfigWidgetMap[ui.arduPlaneLevelButton] = planeLevel;
m_planeLevel = new ApmPlaneLevel(this);
ui.stackedWidget->addWidget(m_planeLevel);
m_buttonToConfigWidgetMap[ui.arduPlaneLevelButton] = m_planeLevel;
connect(ui.arduPlaneLevelButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
radioConfig = new RadioCalibrationConfig(this);
ui.stackedWidget->addWidget(radioConfig);
buttonToConfigWidgetMap[ui.radioCalibrateButton] = radioConfig;
m_radioConfig = new RadioCalibrationConfig(this);
ui.stackedWidget->addWidget(m_radioConfig);
m_buttonToConfigWidgetMap[ui.radioCalibrateButton] = m_radioConfig;
connect(ui.radioCalibrateButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
radio3drConfig = new Radio3DRConfig(this);
ui.stackedWidget->addWidget(radio3drConfig);
buttonToConfigWidgetMap[ui.radio3DRButton] = radio3drConfig;
m_radio3drConfig = new Radio3DRConfig(this);
ui.stackedWidget->addWidget(m_radio3drConfig);
m_buttonToConfigWidgetMap[ui.radio3DRButton] = m_radio3drConfig;
connect(ui.radio3DRButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
batteryConfig = new BatteryMonitorConfig(this);
ui.stackedWidget->addWidget(batteryConfig);
buttonToConfigWidgetMap[ui.batteryMonitorButton] = batteryConfig;
m_batteryConfig = new BatteryMonitorConfig(this);
ui.stackedWidget->addWidget(m_batteryConfig);
m_buttonToConfigWidgetMap[ui.batteryMonitorButton] = m_batteryConfig;
connect(ui.batteryMonitorButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
sonarConfig = new SonarConfig(this);
ui.stackedWidget->addWidget(sonarConfig);
buttonToConfigWidgetMap[ui.sonarButton] = sonarConfig;
m_sonarConfig = new SonarConfig(this);
ui.stackedWidget->addWidget(m_sonarConfig);
m_buttonToConfigWidgetMap[ui.sonarButton] = m_sonarConfig;
connect(ui.sonarButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
airspeedConfig = new AirspeedConfig(this);
ui.stackedWidget->addWidget(airspeedConfig);
buttonToConfigWidgetMap[ui.airspeedButton] = airspeedConfig;
m_airspeedConfig = new AirspeedConfig(this);
ui.stackedWidget->addWidget(m_airspeedConfig);
m_buttonToConfigWidgetMap[ui.airspeedButton] = m_airspeedConfig;
connect(ui.airspeedButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
opticalFlowConfig = new OpticalFlowConfig(this);
ui.stackedWidget->addWidget(opticalFlowConfig);
buttonToConfigWidgetMap[ui.opticalFlowButton] = opticalFlowConfig;
m_opticalFlowConfig = new OpticalFlowConfig(this);
ui.stackedWidget->addWidget(m_opticalFlowConfig);
m_buttonToConfigWidgetMap[ui.opticalFlowButton] = m_opticalFlowConfig;
connect(ui.opticalFlowButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
osdConfig = new OsdConfig(this);
ui.stackedWidget->addWidget(osdConfig);
buttonToConfigWidgetMap[ui.osdButton] = osdConfig;
m_osdConfig = new OsdConfig(this);
ui.stackedWidget->addWidget(m_osdConfig);
m_buttonToConfigWidgetMap[ui.osdButton] = m_osdConfig;
connect(ui.osdButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
cameraGimbalConfig = new CameraGimbalConfig(this);
ui.stackedWidget->addWidget(cameraGimbalConfig);
buttonToConfigWidgetMap[ui.cameraGimbalButton] = cameraGimbalConfig;
m_cameraGimbalConfig = new CameraGimbalConfig(this);
ui.stackedWidget->addWidget(m_cameraGimbalConfig);
m_buttonToConfigWidgetMap[ui.cameraGimbalButton] = m_cameraGimbalConfig;
connect(ui.cameraGimbalButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
antennaTrackerConfig = new AntennaTrackerConfig(this);
ui.stackedWidget->addWidget(antennaTrackerConfig);
buttonToConfigWidgetMap[ui.antennaTrackerButton] = antennaTrackerConfig;
m_antennaTrackerConfig = new AntennaTrackerConfig(this);
ui.stackedWidget->addWidget(m_antennaTrackerConfig);
m_buttonToConfigWidgetMap[ui.antennaTrackerButton] = m_antennaTrackerConfig;
connect(ui.antennaTrackerButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
......@@ -139,9 +139,9 @@ ApmHardwareConfig::ApmHardwareConfig(QWidget *parent) : QWidget(parent)
}
void ApmHardwareConfig::activateStackedWidget()
{
if (buttonToConfigWidgetMap.contains(sender()))
if (m_buttonToConfigWidgetMap.contains(sender()))
{
ui.stackedWidget->setCurrentWidget(buttonToConfigWidgetMap[sender()]);
ui.stackedWidget->setCurrentWidget(m_buttonToConfigWidgetMap[sender()]);
}
}
......
......@@ -58,20 +58,20 @@ public:
explicit ApmHardwareConfig(QWidget *parent = 0);
~ApmHardwareConfig();
private:
FrameTypeConfig *frameConfig;
CompassConfig *compassConfig;
AccelCalibrationConfig *accelConfig;
RadioCalibrationConfig *radioConfig;
FrameTypeConfig *m_frameConfig;
CompassConfig *m_compassConfig;
AccelCalibrationConfig *m_accelConfig;
RadioCalibrationConfig *m_radioConfig;
Radio3DRConfig *radio3drConfig;
BatteryMonitorConfig *batteryConfig;
SonarConfig *sonarConfig;
AirspeedConfig *airspeedConfig;
OpticalFlowConfig *opticalFlowConfig;
OsdConfig *osdConfig;
CameraGimbalConfig *cameraGimbalConfig;
AntennaTrackerConfig *antennaTrackerConfig;
ApmPlaneLevel *planeLevel;
Radio3DRConfig *m_radio3drConfig;
BatteryMonitorConfig *m_batteryConfig;
SonarConfig *m_sonarConfig;
AirspeedConfig *m_airspeedConfig;
OpticalFlowConfig *m_opticalFlowConfig;
OsdConfig *m_osdConfig;
CameraGimbalConfig *m_cameraGimbalConfig;
AntennaTrackerConfig *m_antennaTrackerConfig;
ApmPlaneLevel *m_planeLevel;
private slots:
void activeUASSet(UASInterface *uas);
void activateStackedWidget();
......@@ -79,7 +79,7 @@ private:
Ui::ApmHardwareConfig ui;
//This is a map between the buttons, and the widgets they should be displying
QMap<QObject*,QWidget*> buttonToConfigWidgetMap;
QMap<QObject*,QWidget*> m_buttonToConfigWidgetMap;
};
#endif // APMHARDWARECONFIG_H
......@@ -13,16 +13,21 @@ ApmPlaneLevel::~ApmPlaneLevel()
}
void ApmPlaneLevel::levelClicked()
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
QMessageBox::information(0,"Warning","Be sure the plane is completly level, then click ok");
MAV_CMD command = MAV_CMD_PREFLIGHT_CALIBRATION;
int confirm = 0;
float param1 = 1;
float param2 = 0;
float param3 = 1;
float param4 = 0;
float param5 = 0;
float param6 = 0;
float param7 = 0;
float param1 = 1.0;
float param2 = 0.0;
float param3 = 1.0;
float param4 = 0.0;
float param5 = 0.0;
float param6 = 0.0;
float param7 = 0.0;
int component = 1;
m_uas->executeCommand(command, confirm, param1, param2, param3, param4, param5, param6, param7, component);
QMessageBox::information(0,"Warning","Leveling completed");
......@@ -32,6 +37,7 @@ void ApmPlaneLevel::manualCheckBoxToggled(bool checked)
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
if (checked)
......
#include "ApmSoftwareConfig.h"
#include <QXmlStreamReader>
#include <QDir>
#include <QFile>
#include "ApmSoftwareConfig.h"
ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent)
{
......@@ -17,51 +18,48 @@ ApmSoftwareConfig::ApmSoftwareConfig(QWidget *parent) : QWidget(parent)
ui.arduRoverPidButton->setVisible(false);
ui.arduPlanePidButton->setVisible(false);
flightConfig = new FlightModeConfig(this);
ui.stackedWidget->addWidget(flightConfig);
buttonToConfigWidgetMap[ui.flightModesButton] = flightConfig;
m_flightConfig = new FlightModeConfig(this);
ui.stackedWidget->addWidget(m_flightConfig);
m_buttonToConfigWidgetMap[ui.flightModesButton] = m_flightConfig;
connect(ui.flightModesButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
standardParamConfig = new StandardParamConfig(this);
ui.stackedWidget->addWidget(standardParamConfig);
buttonToConfigWidgetMap[ui.standardParamButton] = standardParamConfig;
m_standardParamConfig = new StandardParamConfig(this);
ui.stackedWidget->addWidget(m_standardParamConfig);
m_buttonToConfigWidgetMap[ui.standardParamButton] = m_standardParamConfig;
connect(ui.standardParamButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
failSafeConfig = new FailSafeConfig(this);
ui.stackedWidget->addWidget(failSafeConfig);
buttonToConfigWidgetMap[ui.failSafeButton] = failSafeConfig;
m_failSafeConfig = new FailSafeConfig(this);
ui.stackedWidget->addWidget(m_failSafeConfig);
m_buttonToConfigWidgetMap[ui.failSafeButton] = m_failSafeConfig;
connect(ui.failSafeButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
advancedParamConfig = new AdvancedParamConfig(this);
ui.stackedWidget->addWidget(advancedParamConfig);
buttonToConfigWidgetMap[ui.advancedParamButton] = advancedParamConfig;
m_advancedParamConfig = new AdvancedParamConfig(this);
ui.stackedWidget->addWidget(m_advancedParamConfig);
m_buttonToConfigWidgetMap[ui.advancedParamButton] = m_advancedParamConfig;
connect(ui.advancedParamButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
advParameterList = new AdvParameterList(this);
ui.stackedWidget->addWidget(advParameterList);
buttonToConfigWidgetMap[ui.advParamListButton] = advParameterList;
m_advParameterList = new AdvParameterList(this);
ui.stackedWidget->addWidget(m_advParameterList);
m_buttonToConfigWidgetMap[ui.advParamListButton] = m_advParameterList;
connect(ui.advParamListButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
arduCopterPidConfig = new ArduCopterPidConfig(this);
ui.stackedWidget->addWidget(arduCopterPidConfig);
buttonToConfigWidgetMap[ui.arduCopterPidButton] = arduCopterPidConfig;
m_arduCopterPidConfig = new ArduCopterPidConfig(this);
ui.stackedWidget->addWidget(m_arduCopterPidConfig);
m_buttonToConfigWidgetMap[ui.arduCopterPidButton] = m_arduCopterPidConfig;
connect(ui.arduCopterPidButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
arduPlanePidConfig = new ArduPlanePidConfig(this);
ui.stackedWidget->addWidget(arduPlanePidConfig);
buttonToConfigWidgetMap[ui.arduPlanePidButton] = arduPlanePidConfig;
m_arduPlanePidConfig = new ArduPlanePidConfig(this);
ui.stackedWidget->addWidget(m_arduPlanePidConfig);
m_buttonToConfigWidgetMap[ui.arduPlanePidButton] = m_arduPlanePidConfig;
connect(ui.arduPlanePidButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
arduRoverPidConfig = new ArduRoverPidConfig(this);
ui.stackedWidget->addWidget(arduRoverPidConfig);
buttonToConfigWidgetMap[ui.arduRoverPidButton] = arduRoverPidConfig;
m_arduRoverPidConfig = new ArduRoverPidConfig(this);
ui.stackedWidget->addWidget(m_arduRoverPidConfig);
m_buttonToConfigWidgetMap[ui.arduRoverPidButton] = m_arduRoverPidConfig;
connect(ui.arduRoverPidButton,SIGNAL(clicked()),this,SLOT(activateStackedWidget()));
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
if (UASManager::instance()->getActiveUAS())
{
activeUASSet(UASManager::instance()->getActiveUAS());
}
activeUASSet(UASManager::instance()->getActiveUAS());
}
ApmSoftwareConfig::~ApmSoftwareConfig()
......@@ -69,9 +67,9 @@ ApmSoftwareConfig::~ApmSoftwareConfig()
}
void ApmSoftwareConfig::activateStackedWidget()
{
if (buttonToConfigWidgetMap.contains(sender()))
if (m_buttonToConfigWidgetMap.contains(sender()))
{
ui.stackedWidget->setCurrentWidget(buttonToConfigWidgetMap[sender()]);
ui.stackedWidget->setCurrentWidget(m_buttonToConfigWidgetMap[sender()]);
}
}
void ApmSoftwareConfig::activeUASSet(UASInterface *uas)
......@@ -296,11 +294,6 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas)
genset["count"] = genarraycount;
}
//Right here we have a single param in memory
name;
docs;
valuemap;
fieldmap;
//standardParamConfig
if (valuemap.size() > 0)
{
QList<QPair<int,QString> > valuelist;
......@@ -310,13 +303,13 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas)
}
if (tab == "Standard")
{
standardParamConfig->addCombo(humanname,docs,name,valuelist);
m_standardParamConfig->addCombo(humanname,docs,name,valuelist);
}
else if (tab == "Advanced")
{
advancedParamConfig->addCombo(humanname,docs,name,valuelist);
m_advancedParamConfig->addCombo(humanname,docs,name,valuelist);
}
advParameterList->setParameterMetaData(name,humanname,docs);
m_advParameterList->setParameterMetaData(name,humanname,docs);
}
else if (fieldmap.size() > 0)
{
......@@ -340,120 +333,23 @@ void ApmSoftwareConfig::activeUASSet(UASInterface *uas)
}
if (tab == "Standard")
{
standardParamConfig->addRange(humanname,docs,name,min,max);
m_standardParamConfig->addRange(humanname,docs,name,min,max);
}
else if (tab == "Advanced")
{
advancedParamConfig->addRange(humanname,docs,name,max,min);
m_advancedParamConfig->addRange(humanname,docs,name,max,min);
}
advParameterList->setParameterMetaData(name,humanname,docs);
m_advParameterList->setParameterMetaData(name,humanname,docs);
}
}
xml.readNext();
}
if (genarraycount > 0)
{
/*
tool = new QGCToolWidget("", this);
tool->addUAS(mav);
tool->setTitle(parametersname);
tool->setObjectName(parametersname);
tool->setSettings(genset);
QList<QString> paramlist = tool->getParamList();
for (int i=0;i<paramlist.size();i++)
{
//Based on the airframe, we add the parameter to different categories.
if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
{
systemTypeToParamMap["FIXED_WING"]->insert(paramlist[i],tool);
}
else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
{
systemTypeToParamMap["QUADROTOR"]->insert(paramlist[i],tool);
}
else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
{
systemTypeToParamMap["GROUND_ROVER"]->insert(paramlist[i],tool);
}
else
{
libParamToWidgetMap->insert(paramlist[i],tool);
}
}
toolWidgets.append(tool);
QGroupBox *box = new QGroupBox(this);
box->setTitle(tool->objectName());
box->setLayout(new QVBoxLayout());
box->layout()->addWidget(tool);
if (valuetype == "vehicles")
{
ui->leftGeneralLayout->addWidget(box);
}
else if (valuetype == "libraries")
{
ui->rightGeneralLayout->addWidget(box);
}
box->hide();
toolToBoxMap[tool] = box;*/
}
if (advarraycount > 0)
{
/*
tool = new QGCToolWidget("", this);
tool->addUAS(mav);
tool->setTitle(parametersname);
tool->setObjectName(parametersname);
tool->setSettings(advset);
QList<QString> paramlist = tool->getParamList();
for (int i=0;i<paramlist.size();i++)
{
//Based on the airframe, we add the parameter to different categories.
if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
{
systemTypeToParamMap["FIXED_WING"]->insert(paramlist[i],tool);
}
else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
{
systemTypeToParamMap["QUADROTOR"]->insert(paramlist[i],tool);
}
else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
{
systemTypeToParamMap["GROUND_ROVER"]->insert(paramlist[i],tool);
}
else
{
libParamToWidgetMap->insert(paramlist[i],tool);
}
}
toolWidgets.append(tool);
QGroupBox *box = new QGroupBox(this);
box->setTitle(tool->objectName());
box->setLayout(new QVBoxLayout());
box->layout()->addWidget(tool);
if (valuetype == "vehicles")
{
ui->leftAdvancedLayout->addWidget(box);
}
else if (valuetype == "libraries")
{
ui->rightAdvancedLayout->addWidget(box);
}
box->hide();
toolToBoxMap[tool] = box;*/
}
}
xml.readNext();
}
}
xml.readNext();
}
}
......
......@@ -28,17 +28,17 @@ private slots:
void activeUASSet(UASInterface *uas);
private:
Ui::ApmSoftwareConfig ui;
BasicPidConfig *basicPidConfig;
FlightModeConfig *flightConfig;
StandardParamConfig *standardParamConfig;
GeoFenceConfig *geoFenceConfig;
FailSafeConfig *failSafeConfig;
AdvancedParamConfig *advancedParamConfig;
ArduCopterPidConfig *arduCopterPidConfig;
ArduPlanePidConfig *arduPlanePidConfig;
ArduRoverPidConfig *arduRoverPidConfig;
AdvParameterList *advParameterList;
QMap<QObject*,QWidget*> buttonToConfigWidgetMap;
BasicPidConfig *m_basicPidConfig;
FlightModeConfig *m_flightConfig;
StandardParamConfig *m_standardParamConfig;
GeoFenceConfig *m_geoFenceConfig;
FailSafeConfig *m_failSafeConfig;
AdvancedParamConfig *m_advancedParamConfig;
ArduCopterPidConfig *m_arduCopterPidConfig;
ArduPlanePidConfig *m_arduPlanePidConfig;
ArduRoverPidConfig *m_arduRoverPidConfig;
AdvParameterList *m_advParameterList;
QMap<QObject*,QWidget*> m_buttonToConfigWidgetMap;
};
#endif // APMSOFTWARECONFIG_H
......@@ -3,126 +3,110 @@
ArduCopterPidConfig::ArduCopterPidConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
nameToBoxMap["STB_RLL_P"] = ui.stabilPitchPSpinBox;
nameToBoxMap["STB_PIT_P"] = ui.stabilRollPSpinBox;
nameToBoxMap["STB_YAW_P"] = ui.stabilYawPSpinBox;
nameToBoxMap["HLD_LAT_P"] = ui.loiterPidPSpinBox;
nameToBoxMap["RATE_RLL_P"] = ui.rateRollPSpinBox;
nameToBoxMap["RATE_RLL_I"] = ui.rateRollISpinBox;
nameToBoxMap["RATE_RLL_D"] = ui.rateRollDSpinBox;
nameToBoxMap["RATE_RLL_IMAX"] = ui.rateRollIMAXSpinBox;
nameToBoxMap["RATE_PIT_P"] = ui.ratePitchPSpinBox;
nameToBoxMap["RATE_PIT_I"] = ui.ratePitchISpinBox;
nameToBoxMap["RATE_PIT_D"] = ui.ratePitchDSpinBox;
nameToBoxMap["RATE_PIT_IMAX"] = ui.ratePitchIMAXSpinBox;
nameToBoxMap["RATE_YAW_P"] = ui.rateYawPSpinBox;
nameToBoxMap["RATE_YAW_I"] = ui.rateYawISpinBox;
nameToBoxMap["RATE_YAW_D"] = ui.rateYawDSpinBox;
nameToBoxMap["RATE_YAW_IMAX"] = ui.rateYawIMAXSpinBox;
nameToBoxMap["LOITER_LAT_P"] = ui.rateLoiterPSpinBox;
nameToBoxMap["LOITER_LAT_I"] = ui.rateLoiterISpinBox;
nameToBoxMap["LOITER_LAT_D"] = ui.rateLoiterDSpinBox;
nameToBoxMap["LOITER_LAT_IMAX"] = ui.rateLoiterIMAXSpinBox;
nameToBoxMap["THR_ACCEL_P"] = ui.throttleAccelPSpinBox;
nameToBoxMap["THR_ACCEL_I"] = ui.throttleAccelISpinBox;
nameToBoxMap["THR_ACCEL_D"] = ui.throttleAccelDSpinBox;
nameToBoxMap["THR_ACCEL_IMAX"] = ui.throttleAccelIMAXSpinBox;
nameToBoxMap["THR_RATE_P"] = ui.throttleRatePSpinBox;
nameToBoxMap["THR_RATE_D"] = ui.throttleDateDSpinBox;
nameToBoxMap["THR_ALT_P"] = ui.altitudeHoldPSpinBox;
nameToBoxMap["WPNAV_SPEED"] = ui.wpNavLoiterSpeedSpinBox;
nameToBoxMap["WPNAV_RADIUS"] = ui.wpNavRadiusSpinBox;
nameToBoxMap["WPNAV_SPEED_DN"] = ui.wpNavSpeedDownSpinBox;
nameToBoxMap["WPNAV_LOIT_SPEED"] = ui.wpNavSpeedSpinBox;
nameToBoxMap["WPNAV_SPEED_UP"] = ui.wpNavSpeedUpSpinBox;
nameToBoxMap["TUNE_HIGH"] = ui.ch6MaxSpinBox;
nameToBoxMap["TUNE_LOW"] = ui.ch6MinSpinBox;
m_nameToBoxMap["STB_RLL_P"] = ui.stabilPitchPSpinBox;
m_nameToBoxMap["STB_PIT_P"] = ui.stabilRollPSpinBox;
m_nameToBoxMap["STB_YAW_P"] = ui.stabilYawPSpinBox;
m_nameToBoxMap["HLD_LAT_P"] = ui.loiterPidPSpinBox;
m_nameToBoxMap["RATE_RLL_P"] = ui.rateRollPSpinBox;
m_nameToBoxMap["RATE_RLL_I"] = ui.rateRollISpinBox;
m_nameToBoxMap["RATE_RLL_D"] = ui.rateRollDSpinBox;
m_nameToBoxMap["RATE_RLL_IMAX"] = ui.rateRollIMAXSpinBox;
m_nameToBoxMap["RATE_PIT_P"] = ui.ratePitchPSpinBox;
m_nameToBoxMap["RATE_PIT_I"] = ui.ratePitchISpinBox;
m_nameToBoxMap["RATE_PIT_D"] = ui.ratePitchDSpinBox;
m_nameToBoxMap["RATE_PIT_IMAX"] = ui.ratePitchIMAXSpinBox;
m_nameToBoxMap["RATE_YAW_P"] = ui.rateYawPSpinBox;
m_nameToBoxMap["RATE_YAW_I"] = ui.rateYawISpinBox;
m_nameToBoxMap["RATE_YAW_D"] = ui.rateYawDSpinBox;
m_nameToBoxMap["RATE_YAW_IMAX"] = ui.rateYawIMAXSpinBox;
m_nameToBoxMap["LOITER_LAT_P"] = ui.rateLoiterPSpinBox;
m_nameToBoxMap["LOITER_LAT_I"] = ui.rateLoiterISpinBox;
m_nameToBoxMap["LOITER_LAT_D"] = ui.rateLoiterDSpinBox;
m_nameToBoxMap["LOITER_LAT_IMAX"] = ui.rateLoiterIMAXSpinBox;
m_nameToBoxMap["THR_ACCEL_P"] = ui.throttleAccelPSpinBox;
m_nameToBoxMap["THR_ACCEL_I"] = ui.throttleAccelISpinBox;
m_nameToBoxMap["THR_ACCEL_D"] = ui.throttleAccelDSpinBox;
m_nameToBoxMap["THR_ACCEL_IMAX"] = ui.throttleAccelIMAXSpinBox;
m_nameToBoxMap["THR_RATE_P"] = ui.throttleRatePSpinBox;
m_nameToBoxMap["THR_RATE_D"] = ui.throttleDateDSpinBox;
m_nameToBoxMap["THR_ALT_P"] = ui.altitudeHoldPSpinBox;
m_nameToBoxMap["WPNAV_SPEED"] = ui.wpNavLoiterSpeedSpinBox;
m_nameToBoxMap["WPNAV_RADIUS"] = ui.wpNavRadiusSpinBox;
m_nameToBoxMap["WPNAV_SPEED_DN"] = ui.wpNavSpeedDownSpinBox;
m_nameToBoxMap["WPNAV_LOIT_SPEED"] = ui.wpNavSpeedSpinBox;
m_nameToBoxMap["WPNAV_SPEED_UP"] = ui.wpNavSpeedUpSpinBox;
m_nameToBoxMap["TUNE_HIGH"] = ui.ch6MaxSpinBox;
m_nameToBoxMap["TUNE_LOW"] = ui.ch6MinSpinBox;
connect(ui.writePushButton,SIGNAL(clicked()),this,SLOT(writeButtonClicked()));
connect(ui.refreshPushButton,SIGNAL(clicked()),this,SLOT(refreshButtonClicked()));
ch6ValueToTextList.append(QPair<int,QString>(0,"CH6_NONE"));
ch6ValueToTextList.append(QPair<int,QString>(1,"CH6_STABILIZE_KP"));
ch6ValueToTextList.append(QPair<int,QString>(2,"CH6_STABILIZE_KI"));
ch6ValueToTextList.append(QPair<int,QString>(3,"CH6_YAW_KP"));
ch6ValueToTextList.append(QPair<int,QString>(24,"CH6_YAW_KI"));
ch6ValueToTextList.append(QPair<int,QString>(4,"CH6_RATE_KP"));
ch6ValueToTextList.append(QPair<int,QString>(5,"CH6_RATE_KI"));
ch6ValueToTextList.append(QPair<int,QString>(6,"CH6_YAW_RATE_KP"));
ch6ValueToTextList.append(QPair<int,QString>(26,"CH6_YAW_RATE_KD"));
ch6ValueToTextList.append(QPair<int,QString>(7,"CH6_THROTTLE_KP"));
ch6ValueToTextList.append(QPair<int,QString>(9,"CH6_RELAY"));
ch6ValueToTextList.append(QPair<int,QString>(10,"CH6_WP_SPEED"));
ch6ValueToTextList.append(QPair<int,QString>(12,"CH6_LOITER_KP"));
ch6ValueToTextList.append(QPair<int,QString>(13,"CH6_HELI_EXTERNAL_GYRO"));
ch6ValueToTextList.append(QPair<int,QString>(14,"CH6_THR_HOLD_KP"));
ch6ValueToTextList.append(QPair<int,QString>(17,"CH6_OPTFLOW_KP"));
ch6ValueToTextList.append(QPair<int,QString>(18,"CH6_OPTFLOW_KI"));
ch6ValueToTextList.append(QPair<int,QString>(19,"CH6_OPTFLOW_KD"));
ch6ValueToTextList.append(QPair<int,QString>(21,"CH6_RATE_KD"));
ch6ValueToTextList.append(QPair<int,QString>(22,"CH6_LOITER_RATE_KP"));
ch6ValueToTextList.append(QPair<int,QString>(23,"CH6_LOITER_RATE_KD"));
ch6ValueToTextList.append(QPair<int,QString>(25,"CH6_ACRO_KP"));
ch6ValueToTextList.append(QPair<int,QString>(27,"CH6_LOITER_KI"));
ch6ValueToTextList.append(QPair<int,QString>(28,"CH6_LOITER_RATE_KI"));
ch6ValueToTextList.append(QPair<int,QString>(29,"CH6_STABILIZE_KD"));
ch6ValueToTextList.append(QPair<int,QString>(30,"CH6_AHRS_YAW_KP"));
ch6ValueToTextList.append(QPair<int,QString>(31,"CH6_AHRS_KP"));
ch6ValueToTextList.append(QPair<int,QString>(32,"CH6_INAV_TC"));
ch6ValueToTextList.append(QPair<int,QString>(33,"CH6_THROTTLE_KI"));
ch6ValueToTextList.append(QPair<int,QString>(34,"CH6_THR_ACCEL_KP"));
ch6ValueToTextList.append(QPair<int,QString>(35,"CH6_THR_ACCEL_KI"));
ch6ValueToTextList.append(QPair<int,QString>(36,"CH6_THR_ACCEL_KD"));
ch6ValueToTextList.append(QPair<int,QString>(38,"CH6_DECLINATION"));
ch6ValueToTextList.append(QPair<int,QString>(39,"CH6_CIRCLE_RATE"));
for (int i=0;i<ch6ValueToTextList.size();i++)
m_ch6ValueToTextList.append(QPair<int,QString>(0,"CH6_NONE"));
m_ch6ValueToTextList.append(QPair<int,QString>(1,"CH6_STABILIZE_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(2,"CH6_STABILIZE_KI"));
m_ch6ValueToTextList.append(QPair<int,QString>(3,"CH6_YAW_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(24,"CH6_YAW_KI"));
m_ch6ValueToTextList.append(QPair<int,QString>(4,"CH6_RATE_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(5,"CH6_RATE_KI"));
m_ch6ValueToTextList.append(QPair<int,QString>(6,"CH6_YAW_RATE_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(26,"CH6_YAW_RATE_KD"));
m_ch6ValueToTextList.append(QPair<int,QString>(7,"CH6_THROTTLE_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(9,"CH6_RELAY"));
m_ch6ValueToTextList.append(QPair<int,QString>(10,"CH6_WP_SPEED"));
m_ch6ValueToTextList.append(QPair<int,QString>(12,"CH6_LOITER_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(13,"CH6_HELI_EXTERNAL_GYRO"));
m_ch6ValueToTextList.append(QPair<int,QString>(14,"CH6_THR_HOLD_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(17,"CH6_OPTFLOW_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(18,"CH6_OPTFLOW_KI"));
m_ch6ValueToTextList.append(QPair<int,QString>(19,"CH6_OPTFLOW_KD"));
m_ch6ValueToTextList.append(QPair<int,QString>(21,"CH6_RATE_KD"));
m_ch6ValueToTextList.append(QPair<int,QString>(22,"CH6_LOITER_RATE_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(23,"CH6_LOITER_RATE_KD"));
m_ch6ValueToTextList.append(QPair<int,QString>(25,"CH6_ACRO_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(27,"CH6_LOITER_KI"));
m_ch6ValueToTextList.append(QPair<int,QString>(28,"CH6_LOITER_RATE_KI"));
m_ch6ValueToTextList.append(QPair<int,QString>(29,"CH6_STABILIZE_KD"));
m_ch6ValueToTextList.append(QPair<int,QString>(30,"CH6_AHRS_YAW_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(31,"CH6_AHRS_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(32,"CH6_INAV_TC"));
m_ch6ValueToTextList.append(QPair<int,QString>(33,"CH6_THROTTLE_KI"));
m_ch6ValueToTextList.append(QPair<int,QString>(34,"CH6_THR_ACCEL_KP"));
m_ch6ValueToTextList.append(QPair<int,QString>(35,"CH6_THR_ACCEL_KI"));
m_ch6ValueToTextList.append(QPair<int,QString>(36,"CH6_THR_ACCEL_KD"));
m_ch6ValueToTextList.append(QPair<int,QString>(38,"CH6_DECLINATION"));
m_ch6ValueToTextList.append(QPair<int,QString>(39,"CH6_CIRCLE_RATE"));
for (int i=0;i<m_ch6ValueToTextList.size();i++)
{
ui.ch6OptComboBox->addItem(ch6ValueToTextList[i].second);
ui.ch6OptComboBox->addItem(m_ch6ValueToTextList[i].second);
}
ch7ValueToTextList.append(QPair<int,QString>(0,"Do nothing"));
ch7ValueToTextList.append(QPair<int,QString>(2,"Flip"));
ch7ValueToTextList.append(QPair<int,QString>(3,"Simple mode"));
ch7ValueToTextList.append(QPair<int,QString>(4,"RTL"));
ch7ValueToTextList.append(QPair<int,QString>(5,"Save Trim"));
ch7ValueToTextList.append(QPair<int,QString>(7,"Save WP"));
ch7ValueToTextList.append(QPair<int,QString>(8,"Multi Mode"));
ch7ValueToTextList.append(QPair<int,QString>(9,"Camera Trigger"));
ch7ValueToTextList.append(QPair<int,QString>(10,"Sonar"));
ch7ValueToTextList.append(QPair<int,QString>(11,"Fence"));
ch7ValueToTextList.append(QPair<int,QString>(12,"ResetToArmedYaw"));
for (int i=0;i<ch7ValueToTextList.size();i++)
m_ch78ValueToTextList.append(QPair<int,QString>(0,"Do nothing"));
m_ch78ValueToTextList.append(QPair<int,QString>(2,"Flip"));
m_ch78ValueToTextList.append(QPair<int,QString>(3,"Simple mode"));
m_ch78ValueToTextList.append(QPair<int,QString>(4,"RTL"));
m_ch78ValueToTextList.append(QPair<int,QString>(5,"Save Trim"));
m_ch78ValueToTextList.append(QPair<int,QString>(7,"Save WP"));
m_ch78ValueToTextList.append(QPair<int,QString>(8,"Multi Mode"));
m_ch78ValueToTextList.append(QPair<int,QString>(9,"Camera Trigger"));
m_ch78ValueToTextList.append(QPair<int,QString>(10,"Sonar"));
m_ch78ValueToTextList.append(QPair<int,QString>(11,"Fence"));
m_ch78ValueToTextList.append(QPair<int,QString>(12,"ResetToArmedYaw"));
for (int i=0;i<m_ch78ValueToTextList.size();i++)
{
ui.ch7OptComboBox->addItem(ch7ValueToTextList[i].second);
ui.ch7OptComboBox->addItem(m_ch78ValueToTextList[i].second);
ui.ch8OptComboBox->addItem(m_ch78ValueToTextList[i].second);
}
ch8ValueToTextList.append(QPair<int,QString>(0,"Do nothing"));
ch8ValueToTextList.append(QPair<int,QString>(2,"Flip"));
ch8ValueToTextList.append(QPair<int,QString>(3,"Simple mode"));
ch8ValueToTextList.append(QPair<int,QString>(4,"RTL"));
ch8ValueToTextList.append(QPair<int,QString>(5,"Save Trim"));
ch8ValueToTextList.append(QPair<int,QString>(7,"Save WP"));
ch8ValueToTextList.append(QPair<int,QString>(8,"Multi Mode"));
ch8ValueToTextList.append(QPair<int,QString>(9,"Camera Trigger"));
ch8ValueToTextList.append(QPair<int,QString>(10,"Sonar"));
ch8ValueToTextList.append(QPair<int,QString>(11,"Fence"));
ch8ValueToTextList.append(QPair<int,QString>(12,"ResetToArmedYaw"));
for (int i=0;i<ch8ValueToTextList.size();i++)
{
ui.ch8OptComboBox->addItem(ch8ValueToTextList[i].second);
}
}
ArduCopterPidConfig::~ArduCopterPidConfig()
......@@ -130,15 +114,15 @@ ArduCopterPidConfig::~ArduCopterPidConfig()
}
void ArduCopterPidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (nameToBoxMap.contains(parameterName))
if (m_nameToBoxMap.contains(parameterName))
{
nameToBoxMap[parameterName]->setValue(value.toDouble());
m_nameToBoxMap[parameterName]->setValue(value.toDouble());
}
else if (parameterName == "TUNE")
{
for (int i=0;i<ch6ValueToTextList.size();i++)
for (int i=0;i<m_ch6ValueToTextList.size();i++)
{
if (ch6ValueToTextList[i].first == value.toInt())
if (m_ch6ValueToTextList[i].first == value.toInt())
{
ui.ch6OptComboBox->setCurrentIndex(i);
}
......@@ -146,9 +130,9 @@ void ArduCopterPidConfig::parameterChanged(int uas, int component, QString param
}
else if (parameterName == "CH7_OPT")
{
for (int i=0;i<ch7ValueToTextList.size();i++)
for (int i=0;i<m_ch78ValueToTextList.size();i++)
{
if (ch7ValueToTextList[i].first == value.toInt())
if (m_ch78ValueToTextList[i].first == value.toInt())
{
ui.ch7OptComboBox->setCurrentIndex(i);
}
......@@ -156,9 +140,9 @@ void ArduCopterPidConfig::parameterChanged(int uas, int component, QString param
}
else if (parameterName == "CH8_OPT")
{
for (int i=0;i<ch8ValueToTextList.size();i++)
for (int i=0;i<m_ch78ValueToTextList.size();i++)
{
if (ch8ValueToTextList[i].first == value.toInt())
if (m_ch78ValueToTextList[i].first == value.toInt())
{
ui.ch8OptComboBox->setCurrentIndex(i);
}
......@@ -169,24 +153,26 @@ void ArduCopterPidConfig::writeButtonClicked()
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
for (QMap<QString,QDoubleSpinBox*>::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
for (QMap<QString,QDoubleSpinBox*>::const_iterator i=m_nameToBoxMap.constBegin();i!=m_nameToBoxMap.constEnd();i++)
{
m_uas->getParamManager()->setParameter(1,i.key(),i.value()->value());
}
m_uas->getParamManager()->setParameter(1,"TUNE",ch8ValueToTextList[ui.ch6OptComboBox->currentIndex()].first);
m_uas->getParamManager()->setParameter(1,"CH7_OPT",ch7ValueToTextList[ui.ch7OptComboBox->currentIndex()].first);
m_uas->getParamManager()->setParameter(1,"CH8_OPT",ch8ValueToTextList[ui.ch8OptComboBox->currentIndex()].first);
m_uas->getParamManager()->setParameter(1,"TUNE",m_ch78ValueToTextList[ui.ch6OptComboBox->currentIndex()].first);
m_uas->getParamManager()->setParameter(1,"CH7_OPT",m_ch78ValueToTextList[ui.ch7OptComboBox->currentIndex()].first);
m_uas->getParamManager()->setParameter(1,"CH8_OPT",m_ch78ValueToTextList[ui.ch8OptComboBox->currentIndex()].first);
}
void ArduCopterPidConfig::refreshButtonClicked()
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
for (QMap<QString,QDoubleSpinBox*>::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
for (QMap<QString,QDoubleSpinBox*>::const_iterator i=m_nameToBoxMap.constBegin();i!=m_nameToBoxMap.constEnd();i++)
{
m_uas->getParamManager()->requestParameterUpdate(1,i.key());
}
......
......@@ -18,10 +18,9 @@ private slots:
void refreshButtonClicked();
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
private:
QList<QPair<int,QString> > ch6ValueToTextList;
QList<QPair<int,QString> > ch7ValueToTextList;
QList<QPair<int,QString> > ch8ValueToTextList;
QMap<QString,QDoubleSpinBox*> nameToBoxMap;
QList<QPair<int,QString> > m_ch6ValueToTextList;
QList<QPair<int,QString> > m_ch78ValueToTextList;
QMap<QString,QDoubleSpinBox*> m_nameToBoxMap;
Ui::ArduCopterPidConfig ui;
};
......
......@@ -5,56 +5,56 @@ ArduPlanePidConfig::ArduPlanePidConfig(QWidget *parent) : AP2ConfigWidget(parent
{
ui.setupUi(this);
nameToBoxMap["RLL2SRV_P"] = ui.servoRollPSpinBox;
nameToBoxMap["RLL2SRV_I"] = ui.servoRollISpinBox;
nameToBoxMap["RLL2SRV_D"] = ui.servoRollDSpinBox;
nameToBoxMap["RLL2SRV_IMAX"] = ui.servoRollIMAXSpinBox;
nameToBoxMap["PTCH2SRV_P"] = ui.servoPitchPSpinBox;
nameToBoxMap["PTCH2SRV_I"] = ui.servoPitchISpinBox;
nameToBoxMap["PTCH2SRV_D"] = ui.servoPitchDSpinBox;
nameToBoxMap["PTCH2SRV_IMAX"] = ui.servoPitchIMAXSpinBox;
nameToBoxMap["YW2SRV_P"] = ui.servoYawPSpinBox;
nameToBoxMap["YW2SRV_I"] = ui.servoYawISpinBox;
nameToBoxMap["YW2SRV_D"] = ui.servoYawDSpinBox;
nameToBoxMap["YW2SRV_IMAX"] = ui.servoYawIMAXSpinBox;
nameToBoxMap["ALT2PTCH_P"] = ui.navAltPSpinBox;
nameToBoxMap["ALT2PTCH_I"] = ui.navAltISpinBox;
nameToBoxMap["ALT2PTCH_D"] = ui.navAltDSpinBox;
nameToBoxMap["ALT2PTCH_IMAX"] = ui.navAltIMAXSpinBox;
nameToBoxMap["ARSP2PTCH_P"] = ui.navASPSpinBox;
nameToBoxMap["ARSP2PTCH_I"] = ui.navASISpinBox;
nameToBoxMap["ARSP2PTCH_D"] = ui.navASDSpinBox;
nameToBoxMap["ARSP2PTCH_IMAX"] = ui.navASIMAXSpinBox;
nameToBoxMap["ENRGY2THR_P"] = ui.energyPSpinBox;
nameToBoxMap["ENRGY2THR_I"] = ui.energyISpinBox;
nameToBoxMap["ENRGY2THR_D"] = ui.energyDSpinBox;
nameToBoxMap["ENRGY2THR_IMAX"] = ui.energyIMAXSpinBox;
nameToBoxMap["KFF_PTCH2THR"] = ui.otherPitchCompSpinBox;
nameToBoxMap["KFF_PTCHCOMP"] = ui.otherPtTSpinBox;
nameToBoxMap["KFF_RDDRMIX"] = ui.otherRudderMixSpinBox;
nameToBoxMap["TRIM_THROTTLE"] = ui.throttleCruiseSpinBox;
nameToBoxMap["THR_FS_VALUE"] = ui.throttleFSSpinBox;
nameToBoxMap["THR_MAX"] = ui.throttleMaxSpinBox;
nameToBoxMap["THR_MIN"] = ui.throttleMinSpinBox;
nameToBoxMap["TRIM_ARSPD_CM"] = ui.airspeedCruiseSpinBox;
nameToBoxMap["ARSPD_FBW_MAX"] = ui.airspeedFBWMaxSpinBox;
nameToBoxMap["ARSPD_FBW_MIN"] = ui.airspeedFBWMinSpinBox;
nameToBoxMap["ARSPD_RATIO"] = ui.airspeedRatioSpinBox;
nameToBoxMap["NAVL1_DAMPING"] = ui.l1DampingSpinBox;
nameToBoxMap["NAVL1_PERIOD"] = ui.l1PeriodSpinBox;
nameToBoxMap["LIM_ROLL_CD"] = ui.navBankMaxSpinBox;
nameToBoxMap["LIM_PITCH_MAX"] = ui.navPitchMaxSpinBox;
nameToBoxMap["LIM_PITCH_MIN"] = ui.navPitchMinSpinBox;
m_nameToBoxMap["RLL2SRV_P"] = ui.servoRollPSpinBox;
m_nameToBoxMap["RLL2SRV_I"] = ui.servoRollISpinBox;
m_nameToBoxMap["RLL2SRV_D"] = ui.servoRollDSpinBox;
m_nameToBoxMap["RLL2SRV_IMAX"] = ui.servoRollIMAXSpinBox;
m_nameToBoxMap["PTCH2SRV_P"] = ui.servoPitchPSpinBox;
m_nameToBoxMap["PTCH2SRV_I"] = ui.servoPitchISpinBox;
m_nameToBoxMap["PTCH2SRV_D"] = ui.servoPitchDSpinBox;
m_nameToBoxMap["PTCH2SRV_IMAX"] = ui.servoPitchIMAXSpinBox;
m_nameToBoxMap["YW2SRV_P"] = ui.servoYawPSpinBox;
m_nameToBoxMap["YW2SRV_I"] = ui.servoYawISpinBox;
m_nameToBoxMap["YW2SRV_D"] = ui.servoYawDSpinBox;
m_nameToBoxMap["YW2SRV_IMAX"] = ui.servoYawIMAXSpinBox;
m_nameToBoxMap["ALT2PTCH_P"] = ui.navAltPSpinBox;
m_nameToBoxMap["ALT2PTCH_I"] = ui.navAltISpinBox;
m_nameToBoxMap["ALT2PTCH_D"] = ui.navAltDSpinBox;
m_nameToBoxMap["ALT2PTCH_IMAX"] = ui.navAltIMAXSpinBox;
m_nameToBoxMap["ARSP2PTCH_P"] = ui.navASPSpinBox;
m_nameToBoxMap["ARSP2PTCH_I"] = ui.navASISpinBox;
m_nameToBoxMap["ARSP2PTCH_D"] = ui.navASDSpinBox;
m_nameToBoxMap["ARSP2PTCH_IMAX"] = ui.navASIMAXSpinBox;
m_nameToBoxMap["ENRGY2THR_P"] = ui.energyPSpinBox;
m_nameToBoxMap["ENRGY2THR_I"] = ui.energyISpinBox;
m_nameToBoxMap["ENRGY2THR_D"] = ui.energyDSpinBox;
m_nameToBoxMap["ENRGY2THR_IMAX"] = ui.energyIMAXSpinBox;
m_nameToBoxMap["KFF_PTCH2THR"] = ui.otherPitchCompSpinBox;
m_nameToBoxMap["KFF_PTCHCOMP"] = ui.otherPtTSpinBox;
m_nameToBoxMap["KFF_RDDRMIX"] = ui.otherRudderMixSpinBox;
m_nameToBoxMap["TRIM_THROTTLE"] = ui.throttleCruiseSpinBox;
m_nameToBoxMap["THR_FS_VALUE"] = ui.throttleFSSpinBox;
m_nameToBoxMap["THR_MAX"] = ui.throttleMaxSpinBox;
m_nameToBoxMap["THR_MIN"] = ui.throttleMinSpinBox;
m_nameToBoxMap["TRIM_ARSPD_CM"] = ui.airspeedCruiseSpinBox;
m_nameToBoxMap["ARSPD_FBW_MAX"] = ui.airspeedFBWMaxSpinBox;
m_nameToBoxMap["ARSPD_FBW_MIN"] = ui.airspeedFBWMinSpinBox;
m_nameToBoxMap["ARSPD_RATIO"] = ui.airspeedRatioSpinBox;
m_nameToBoxMap["NAVL1_DAMPING"] = ui.l1DampingSpinBox;
m_nameToBoxMap["NAVL1_PERIOD"] = ui.l1PeriodSpinBox;
m_nameToBoxMap["LIM_ROLL_CD"] = ui.navBankMaxSpinBox;
m_nameToBoxMap["LIM_PITCH_MAX"] = ui.navPitchMaxSpinBox;
m_nameToBoxMap["LIM_PITCH_MIN"] = ui.navPitchMinSpinBox;
connect(ui.writePushButton,SIGNAL(clicked()),this,SLOT(writeButtonClicked()));
connect(ui.refreshPushButton,SIGNAL(clicked()),this,SLOT(refreshButtonClicked()));
......@@ -66,18 +66,19 @@ ArduPlanePidConfig::~ArduPlanePidConfig()
}
void ArduPlanePidConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (nameToBoxMap.contains(parameterName))
if (m_nameToBoxMap.contains(parameterName))
{
nameToBoxMap[parameterName]->setValue(value.toDouble());
m_nameToBoxMap[parameterName]->setValue(value.toDouble());
}
}
void ArduPlanePidConfig::writeButtonClicked()
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
for (QMap<QString,QDoubleSpinBox*>::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
for (QMap<QString,QDoubleSpinBox*>::const_iterator i=m_nameToBoxMap.constBegin();i!=m_nameToBoxMap.constEnd();i++)
{
m_uas->getParamManager()->setParameter(1,i.key(),i.value()->value());
}
......@@ -87,9 +88,10 @@ void ArduPlanePidConfig::refreshButtonClicked()
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
for (QMap<QString,QDoubleSpinBox*>::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
for (QMap<QString,QDoubleSpinBox*>::const_iterator i=m_nameToBoxMap.constBegin();i!=m_nameToBoxMap.constEnd();i++)
{
m_uas->getParamManager()->requestParameterUpdate(1,i.key());
}
......
......@@ -17,7 +17,7 @@ private slots:
void writeButtonClicked();
void refreshButtonClicked();
private:
QMap<QString,QDoubleSpinBox*> nameToBoxMap;
QMap<QString,QDoubleSpinBox*> m_nameToBoxMap;
Ui::ArduPlanePidConfig ui;
};
......
......@@ -49,6 +49,7 @@ void ArduRoverPidConfig::writeButtonClicked()
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
for (QMap<QString,QDoubleSpinBox*>::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
......@@ -61,6 +62,7 @@ void ArduRoverPidConfig::refreshButtonClicked()
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
for (QMap<QString,QDoubleSpinBox*>::const_iterator i=nameToBoxMap.constBegin();i!=nameToBoxMap.constEnd();i++)
......
......@@ -4,11 +4,11 @@
BatteryMonitorConfig::BatteryMonitorConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
ui.monitorComboBox->addItem("0: Disabled");
ui.monitorComboBox->addItem("3: Battery Volts");
ui.monitorComboBox->addItem("4: Voltage and Current");
ui.monitorComboBox->addItem(tr("0: Disabled"));
ui.monitorComboBox->addItem(tr("3: Battery Volts"));
ui.monitorComboBox->addItem(tr("4: Voltage and Current"));
ui.sensorComboBox->addItem("0: Other");
ui.sensorComboBox->addItem(tr("0: Other"));
ui.sensorComboBox->addItem("1: AttoPilot 45A");
ui.sensorComboBox->addItem("2: AttoPilot 90A");
ui.sensorComboBox->addItem("3: AttoPilot 180A");
......@@ -34,19 +34,24 @@ BatteryMonitorConfig::BatteryMonitorConfig(QWidget *parent) : AP2ConfigWidget(pa
}
void BatteryMonitorConfig::activeUASSet(UASInterface *uas)
{
if (m_uas)
{
disconnect(m_uas,SIGNAL(batteryChanged(UASInterface*,double,double,double,int)),this,SLOT(batteryChanged(UASInterface*,double,double,double,int)));
}
AP2ConfigWidget::activeUASSet(uas);
if (!uas)
{
return;
}
connect(uas,SIGNAL(batteryChanged(UASInterface*,double,double,double,int)),this,SLOT(batteryChanged(UASInterface*,double,double,double,int)));
AP2ConfigWidget::activeUASSet(uas);
}
void BatteryMonitorConfig::calcDividerSet()
{
if (!m_uas)
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
showNullMAVErrorMessageBox();
return;
}
bool ok = false;
......@@ -63,7 +68,7 @@ void BatteryMonitorConfig::ampsPerVoltSet()
{
if (!m_uas)
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
showNullMAVErrorMessageBox();
return;
}
bool ok = false;
......@@ -80,7 +85,7 @@ void BatteryMonitorConfig::batteryCapacitySet()
{
if (!m_uas)
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
showNullMAVErrorMessageBox();
return;
}
bool ok = false;
......@@ -98,10 +103,10 @@ void BatteryMonitorConfig::monitorCurrentIndexChanged(int index)
{
if (!m_uas)
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
showNullMAVErrorMessageBox();
return;
}
if (index == 0)
if (index == 0) //Battery Monitor Disabled
{
m_uas->getParamManager()->setParameter(1,"BATT_VOLT_PIN",-1);
m_uas->getParamManager()->setParameter(1,"BATT_CURR_PIN",-1);
......@@ -114,7 +119,7 @@ void BatteryMonitorConfig::monitorCurrentIndexChanged(int index)
ui.calcVoltsLineEdit->setEnabled(false);
ui.ampsPerVoltsLineEdit->setEnabled(false);
}
else if (index == 1)
else if (index == 1) //Monitor voltage only
{
m_uas->getParamManager()->setParameter(1,"BATT_MONITOR",3);
ui.sensorComboBox->setEnabled(false);
......@@ -124,7 +129,7 @@ void BatteryMonitorConfig::monitorCurrentIndexChanged(int index)
ui.calcVoltsLineEdit->setEnabled(false);
ui.ampsPerVoltsLineEdit->setEnabled(false);
}
else if (index == 2)
else if (index == 2) //Monitor voltage and current
{
m_uas->getParamManager()->setParameter(1,"BATT_MONITOR",4);
ui.sensorComboBox->setEnabled(true);
......@@ -139,45 +144,39 @@ void BatteryMonitorConfig::monitorCurrentIndexChanged(int index)
}
void BatteryMonitorConfig::sensorCurrentIndexChanged(int index)
{
float maxvolt = 0;
float maxamps = 0;
float mvpervolt = 0;
float mvperamp = 0;
float topvolt = 0;
float topamps = 0;
float maxvolt = 0.0;
float maxamps = 0.0;
float mvpervolt = 0.0;
float mvperamp = 0.0;
float topvolt = 0.0;
float topamps = 0.0;
if (index == 1)
{
//atto 45
//atto 45 see https://www.sparkfun.com/products/10643
maxvolt = 13.6;
maxamps = 44.7;
mvpervolt = 242.3;
mvperamp = 73.20;
}
else if (index == 2)
{
//atto 90
maxvolt = 50;
//atto 90 see https://www.sparkfun.com/products/9028
maxvolt = 51.8;
maxamps = 89.4;
mvpervolt = 63.69;
mvperamp = 36.60;
}
else if (index == 3)
{
//atto 180
maxvolt = 50;
//atto 180 see https://www.sparkfun.com/products/10644
maxvolt = 51.8;
maxamps = 178.8;
mvpervolt = 63.69;
mvperamp = 18.30;
}
else if (index == 4)
{
//3dr
maxvolt = 50;
maxamps = 90;
mvpervolt = 100;
mvperamp = 55.55;
maxvolt = 50.0;
maxamps = 90.0;
}
mvpervolt = calculatemVPerVolt(3.3,maxvolt);
mvperamp = calculatemVPerAmp(3.3,maxamps);
if (index == 0)
{
//Other
......@@ -197,12 +196,21 @@ void BatteryMonitorConfig::sensorCurrentIndexChanged(int index)
ui.measuredVoltsLineEdit->setEnabled(false);
}
}
float BatteryMonitorConfig::calculatemVPerAmp(float maxvoltsout,float maxamps)
{
return (1000.0 * (maxvoltsout/maxamps));
}
float BatteryMonitorConfig::calculatemVPerVolt(float maxvoltsout,float maxvolts)
{
return (1000.0 * (maxvoltsout/maxvolts));
}
void BatteryMonitorConfig::apmVerCurrentIndexChanged(int index)
{
if (!m_uas)
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
showNullMAVErrorMessageBox();
return;
}
if (index == 0) //APM1
......
......@@ -24,6 +24,8 @@ private slots:
void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds);
private:
Ui::BatteryMonitorConfig ui;
inline float calculatemVPerAmp(float maxvoltsout,float maxamps);
inline float calculatemVPerVolt(float maxvoltsout,float maxvolts);
};
#endif // BATTERYMONITORCONFIG_H
......@@ -150,7 +150,7 @@
<x>160</x>
<y>70</y>
<width>281</width>
<height>80</height>
<height>91</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_3" stretch="0,1">
......
#include "CameraGimbalConfig.h"
#include <QMessageBox>
#include <QDebug>
#include "CameraGimbalConfig.h"
CameraGimbalConfig::CameraGimbalConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
ui.tiltChannelComboBox->addItem("Disable");
ui.tiltChannelComboBox->addItem(tr("Disable"));
ui.tiltChannelComboBox->addItem("RC5");
ui.tiltChannelComboBox->addItem("RC6");
ui.tiltChannelComboBox->addItem("RC7");
......@@ -12,13 +14,13 @@ CameraGimbalConfig::CameraGimbalConfig(QWidget *parent) : AP2ConfigWidget(parent
ui.tiltChannelComboBox->addItem("RC10");
ui.tiltChannelComboBox->addItem("RC11");
ui.tiltInputChannelComboBox->addItem("Disable");
ui.tiltInputChannelComboBox->addItem(tr("Disable"));
ui.tiltInputChannelComboBox->addItem("RC5");
ui.tiltInputChannelComboBox->addItem("RC6");
ui.tiltInputChannelComboBox->addItem("RC7");
ui.tiltInputChannelComboBox->addItem("RC8");
ui.rollChannelComboBox->addItem("Disable");
ui.rollChannelComboBox->addItem(tr("Disable"));
ui.rollChannelComboBox->addItem("RC5");
ui.rollChannelComboBox->addItem("RC6");
ui.rollChannelComboBox->addItem("RC7");
......@@ -26,14 +28,14 @@ CameraGimbalConfig::CameraGimbalConfig(QWidget *parent) : AP2ConfigWidget(parent
ui.rollChannelComboBox->addItem("RC10");
ui.rollChannelComboBox->addItem("RC11");
ui.rollInputChannelComboBox->addItem("Disable");
ui.rollInputChannelComboBox->addItem(tr("Disable"));
ui.rollInputChannelComboBox->addItem("RC5");
ui.rollInputChannelComboBox->addItem("RC6");
ui.rollInputChannelComboBox->addItem("RC7");
ui.rollInputChannelComboBox->addItem("RC8");
ui.panChannelComboBox->addItem("Disable");
ui.panChannelComboBox->addItem(tr("Disable"));
ui.panChannelComboBox->addItem("RC5");
ui.panChannelComboBox->addItem("RC6");
ui.panChannelComboBox->addItem("RC7");
......@@ -41,16 +43,16 @@ CameraGimbalConfig::CameraGimbalConfig(QWidget *parent) : AP2ConfigWidget(parent
ui.panChannelComboBox->addItem("RC10");
ui.panChannelComboBox->addItem("RC11");
ui.panInputChannelComboBox->addItem("Disable");
ui.panInputChannelComboBox->addItem(tr("Disable"));
ui.panInputChannelComboBox->addItem("RC5");
ui.panInputChannelComboBox->addItem("RC6");
ui.panInputChannelComboBox->addItem("RC7");
ui.panInputChannelComboBox->addItem("RC8");
ui.shutterChannelComboBox->addItem("Disable");
ui.shutterChannelComboBox->addItem("Relay");
ui.shutterChannelComboBox->addItem("Transistor");
ui.shutterChannelComboBox->addItem(tr("Disable"));
ui.shutterChannelComboBox->addItem(tr("Relay"));
ui.shutterChannelComboBox->addItem(tr("Transistor"));
ui.shutterChannelComboBox->addItem("RC5");
ui.shutterChannelComboBox->addItem("RC6");
ui.shutterChannelComboBox->addItem("RC7");
......@@ -100,13 +102,13 @@ void CameraGimbalConfig::updateTilt()
{
if (!m_uas)
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
showNullMAVErrorMessageBox();
return;
}
if (!tiltPrefix.isEmpty())
if (!m_tiltPrefix.isEmpty())
{
//We need to set this to 0 for disabled.
m_uas->getParamManager()->setParameter(1,tiltPrefix + "FUNCTION",0);
m_uas->getParamManager()->setParameter(1,m_tiltPrefix + "FUNCTION",0);
}
if (ui.tiltChannelComboBox->currentIndex() == 0)
{
......@@ -134,7 +136,7 @@ void CameraGimbalConfig::updateRoll()
{
if (!m_uas)
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
showNullMAVErrorMessageBox();
return;
}
m_uas->getParamManager()->setParameter(1,ui.rollChannelComboBox->currentText() + "_FUNCTION",8);
......@@ -157,7 +159,7 @@ void CameraGimbalConfig::updatePan()
{
if (!m_uas)
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
showNullMAVErrorMessageBox();
return;
}
m_uas->getParamManager()->setParameter(1,ui.panChannelComboBox->currentText() + "_FUNCTION",6);
......@@ -180,7 +182,7 @@ void CameraGimbalConfig::updateShutter()
{
if (!m_uas)
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
showNullMAVErrorMessageBox();
return;
}
if (ui.shutterChannelComboBox->currentIndex() == 0) //Disabled
......@@ -216,24 +218,6 @@ CameraGimbalConfig::~CameraGimbalConfig()
void CameraGimbalConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
connect(ui.tiltInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
disconnect(ui.tiltInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
connect(ui.panInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
disconnect(ui.panInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
connect(ui.rollInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
disconnect(ui.rollInputChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
if (parameterName == "MNT_ANGMIN_TIL") //TILT
{
ui.tiltAngleMinSpinBox->setValue(value.toInt() / 100.0);
......@@ -327,7 +311,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
}
connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
}
if (parameterName.startsWith(shutterPrefix) && !shutterPrefix.isEmpty())
if (parameterName.startsWith(m_shutterPrefix) && !m_shutterPrefix.isEmpty())
{
if (parameterName.endsWith("MIN"))
{
......@@ -338,7 +322,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
ui.shutterServoMaxSpinBox->setValue(value.toInt());
}
}
else if (parameterName.startsWith(tiltPrefix) && !tiltPrefix.isEmpty())
else if (parameterName.startsWith(m_tiltPrefix) && !m_tiltPrefix.isEmpty())
{
if (parameterName.endsWith("MIN"))
{
......@@ -360,7 +344,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
}
}
}
else if (parameterName.startsWith(rollPrefix) && !rollPrefix.isEmpty())
else if (parameterName.startsWith(m_rollPrefix) && !m_rollPrefix.isEmpty())
{
if (parameterName.endsWith("MIN"))
{
......@@ -382,7 +366,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
}
}
}
else if (parameterName.startsWith(panPrefix) && !panPrefix.isEmpty())
else if (parameterName.startsWith(m_panPrefix) && !m_panPrefix.isEmpty())
{
if (parameterName.endsWith("MIN"))
{
......@@ -412,7 +396,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
ui.shutterChannelComboBox->setCurrentIndex(3);
connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
shutterPrefix = "RC5_";
m_shutterPrefix = "RC5_";
}
else if (value.toInt() == 8)
{
......@@ -420,7 +404,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
ui.rollChannelComboBox->setCurrentIndex(1);
connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
rollPrefix = "RC5_";
m_rollPrefix = "RC5_";
}
else if (value.toInt() == 7)
{
......@@ -428,7 +412,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
ui.tiltChannelComboBox->setCurrentIndex(1);
connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
tiltPrefix = "RC5_";
m_tiltPrefix = "RC5_";
}
else if (value.toInt() == 6)
{
......@@ -436,7 +420,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
ui.panChannelComboBox->setCurrentIndex(1);
connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
panPrefix = "RC5_";
m_panPrefix = "RC5_";
}
m_uas->getParamManager()->requestParameterUpdate(1,"RC5_MIN");
m_uas->getParamManager()->requestParameterUpdate(1,"RC5_MAX");
......@@ -450,7 +434,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
ui.shutterChannelComboBox->setCurrentIndex(4);
connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
shutterPrefix = "RC6_";
m_shutterPrefix = "RC6_";
}
else if (value.toInt() == 8)
{
......@@ -458,7 +442,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
ui.rollChannelComboBox->setCurrentIndex(2);
connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
rollPrefix = "RC6_";
m_rollPrefix = "RC6_";
}
else if (value.toInt() == 7)
{
......@@ -466,7 +450,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
ui.tiltChannelComboBox->setCurrentIndex(2);
connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
tiltPrefix = "RC6_";
m_tiltPrefix = "RC6_";
}
else if (value.toInt() == 6)
{
......@@ -474,7 +458,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
ui.panChannelComboBox->setCurrentIndex(2);
connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
panPrefix = "RC6_";
m_panPrefix = "RC6_";
}
m_uas->getParamManager()->requestParameterUpdate(1,"RC6_MIN");
m_uas->getParamManager()->requestParameterUpdate(1,"RC6_MAX");
......@@ -488,7 +472,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
ui.shutterChannelComboBox->setCurrentIndex(5);
connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
shutterPrefix = "RC7_";
m_shutterPrefix = "RC7_";
}
else if (value.toInt() == 8)
{
......@@ -496,7 +480,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
ui.rollChannelComboBox->setCurrentIndex(3);
connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
rollPrefix = "RC7_";
m_rollPrefix = "RC7_";
}
else if (value.toInt() == 7)
{
......@@ -504,7 +488,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
ui.tiltChannelComboBox->setCurrentIndex(3);
connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
tiltPrefix = "RC7_";
m_tiltPrefix = "RC7_";
}
else if (value.toInt() == 6)
{
......@@ -512,7 +496,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
ui.panChannelComboBox->setCurrentIndex(3);
connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
panPrefix = "RC7_";
m_panPrefix = "RC7_";
}
m_uas->getParamManager()->requestParameterUpdate(1,"RC7_MIN");
m_uas->getParamManager()->requestParameterUpdate(1,"RC7_MAX");
......@@ -526,7 +510,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
ui.shutterChannelComboBox->setCurrentIndex(6);
connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
shutterPrefix = "RC8_";
m_shutterPrefix = "RC8_";
}
else if (value.toInt() == 8)
{
......@@ -534,7 +518,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
ui.rollChannelComboBox->setCurrentIndex(4);
connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
rollPrefix = "RC8_";
m_rollPrefix = "RC8_";
}
else if (value.toInt() == 7)
{
......@@ -542,7 +526,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
ui.tiltChannelComboBox->setCurrentIndex(4);
connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
tiltPrefix = "RC8_";
m_tiltPrefix = "RC8_";
}
else if (value.toInt() == 6)
{
......@@ -550,7 +534,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
ui.panChannelComboBox->setCurrentIndex(4);
connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
panPrefix = "RC8_";
m_panPrefix = "RC8_";
}
m_uas->getParamManager()->requestParameterUpdate(1,"RC8_MIN");
m_uas->getParamManager()->requestParameterUpdate(1,"RC8_MAX");
......@@ -564,7 +548,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
ui.shutterChannelComboBox->setCurrentIndex(7);
connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
shutterPrefix = "RC10_";
m_shutterPrefix = "RC10_";
}
else if (value.toInt() == 8)
{
......@@ -572,7 +556,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
ui.rollChannelComboBox->setCurrentIndex(5);
connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
rollPrefix = "RC10_";
m_rollPrefix = "RC10_";
}
else if (value.toInt() == 7)
{
......@@ -580,7 +564,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
ui.tiltChannelComboBox->setCurrentIndex(5);
connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
tiltPrefix = "RC10_";
m_tiltPrefix = "RC10_";
}
else if (value.toInt() == 6)
{
......@@ -588,7 +572,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
ui.panChannelComboBox->setCurrentIndex(5);
connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
panPrefix = "RC10_";
m_panPrefix = "RC10_";
}
m_uas->getParamManager()->requestParameterUpdate(1,"RC10_MIN");
m_uas->getParamManager()->requestParameterUpdate(1,"RC10_MAX");
......@@ -602,7 +586,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
ui.shutterChannelComboBox->setCurrentIndex(8);
connect(ui.shutterChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateShutter()));
shutterPrefix = "RC11_";
m_shutterPrefix = "RC11_";
}
else if (value.toInt() == 8)
{
......@@ -610,7 +594,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
ui.rollChannelComboBox->setCurrentIndex(6);
connect(ui.rollChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateRoll()));
rollPrefix = "RC11_";
m_rollPrefix = "RC11_";
}
else if (value.toInt() == 7)
{
......@@ -618,7 +602,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
ui.tiltChannelComboBox->setCurrentIndex(6);
connect(ui.tiltChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updateTilt()));
tiltPrefix = "RC11_";
m_tiltPrefix = "RC11_";
}
else if (value.toInt() == 6)
{
......@@ -626,7 +610,7 @@ void CameraGimbalConfig::parameterChanged(int uas, int component, QString parame
disconnect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
ui.panChannelComboBox->setCurrentIndex(6);
connect(ui.panChannelComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(updatePan()));
panPrefix = "RC11_";
m_panPrefix = "RC11_";
}
m_uas->getParamManager()->requestParameterUpdate(1,"RC11_MIN");
m_uas->getParamManager()->requestParameterUpdate(1,"RC11_MAX");
......
......@@ -21,10 +21,10 @@ private slots:
private:
Ui::CameraGimbalConfig ui;
QString shutterPrefix;
QString rollPrefix;
QString tiltPrefix;
QString panPrefix;
QString m_shutterPrefix;
QString m_rollPrefix;
QString m_tiltPrefix;
QString m_panPrefix;
};
#endif // CAMERAGIMBALCONFIG_H
#include "CompassConfig.h"
CompassConfig::CompassConfig(QWidget *parent) : QWidget(parent)
CompassConfig::CompassConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
m_uas=0;
ui.setupUi(this);
......@@ -13,9 +13,6 @@ CompassConfig::CompassConfig(QWidget *parent) : QWidget(parent)
connect(ui.autoDecCheckBox,SIGNAL(clicked(bool)),this,SLOT(autoDecClicked(bool)));
connect(ui.orientationComboBox,SIGNAL(currentIndexChanged(int)),this,SLOT(orientationComboChanged(int)));
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
activeUASSet(UASManager::instance()->getActiveUAS());
ui.orientationComboBox->addItem("ROTATION_NONE");
ui.orientationComboBox->addItem("ROTATION_YAW_45");
ui.orientationComboBox->addItem("ROTATION_YAW_90");
......@@ -47,16 +44,6 @@ CompassConfig::CompassConfig(QWidget *parent) : QWidget(parent)
CompassConfig::~CompassConfig()
{
}
void CompassConfig::activeUASSet(UASInterface *uas)
{
if (!uas) return;
if (!m_uas)
{
disconnect(m_uas,SIGNAL(parameterChanged(int,int,QString,QVariant)),this,SLOT(parameterChanged(int,int,QString,QVariant)));
}
m_uas = uas;
connect(m_uas,SIGNAL(parameterChanged(int,int,QString,QVariant)),this,SLOT(parameterChanged(int,int,QString,QVariant)));
}
void CompassConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (parameterName == "MAG_ENABLE")
......
......@@ -5,7 +5,8 @@
#include "ui_CompassConfig.h"
#include "UASManager.h"
#include "UASInterface.h"
class CompassConfig : public QWidget
#include "AP2ConfigWidget.h"
class CompassConfig : public AP2ConfigWidget
{
Q_OBJECT
......@@ -13,7 +14,6 @@ public:
explicit CompassConfig(QWidget *parent = 0);
~CompassConfig();
private slots:
void activeUASSet(UASInterface *uas);
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
void enableClicked(bool enabled);
void autoDecClicked(bool enabled);
......
......@@ -87,6 +87,7 @@ void FailSafeConfig::gcsChecked(bool checked)
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
if (checked)
......@@ -103,6 +104,7 @@ void FailSafeConfig::throttleActionChecked(bool checked)
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
if (checked)
......@@ -119,6 +121,7 @@ void FailSafeConfig::throttleChecked(bool checked)
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
if (checked)
......@@ -135,6 +138,7 @@ void FailSafeConfig::throttlePwmChanged()
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
m_uas->setParameter(1,"THR_FS_VALUE",ui.throttlePwmSpinBox->value());
......@@ -144,6 +148,7 @@ void FailSafeConfig::throttleFailSafeChanged(int index)
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
m_uas->setParameter(1,"FS_THR_ENABLE",index);
......@@ -153,6 +158,7 @@ void FailSafeConfig::fsLongClicked(bool checked)
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
if (checked)
......@@ -169,6 +175,7 @@ void FailSafeConfig::fsShortClicked(bool checked)
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
if (checked)
......@@ -185,6 +192,7 @@ void FailSafeConfig::batteryFailChecked(bool checked)
{
if (!m_uas)
{
showNullMAVErrorMessageBox();
return;
}
if (checked)
......@@ -202,11 +210,21 @@ FailSafeConfig::~FailSafeConfig()
}
void FailSafeConfig::activeUASSet(UASInterface *uas)
{
if (m_uas)
{
disconnect(m_uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanges(int,float)));
disconnect(m_uas,SIGNAL(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float)),this,SLOT(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float)));
disconnect(m_uas,SIGNAL(armingChanged(bool)),this,SLOT(armingChanged(bool)));
}
AP2ConfigWidget::activeUASSet(uas);
connect(uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanges(int,float)));
connect(uas,SIGNAL(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float)),this,SLOT(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float)));
connect(uas,SIGNAL(armingChanged(bool)),this,SLOT(armingChanged(bool)));
if (uas->getSystemType() == MAV_TYPE_FIXED_WING)
if (!uas)
{
return;
}
connect(m_uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanges(int,float)));
connect(m_uas,SIGNAL(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float)),this,SLOT(hilActuatorsChanged(uint64_t,float,float,float,float,float,float,float,float)));
connect(m_uas,SIGNAL(armingChanged(bool)),this,SLOT(armingChanged(bool)));
if (m_uas->getSystemType() == MAV_TYPE_FIXED_WING)
{
ui.batteryFailCheckBox->setVisible(false);
ui.throttleFailSafeComboBox->setVisible(false);
......@@ -221,7 +239,7 @@ void FailSafeConfig::activeUASSet(UASInterface *uas)
ui.fsLongCheckBox->setVisible(true);
ui.fsShortCheckBox->setVisible(true);
}
else if (uas->getSystemType() == MAV_TYPE_QUADROTOR)
else if (m_uas->getSystemType() == MAV_TYPE_QUADROTOR)
{
ui.batteryFailCheckBox->setVisible(true);
ui.throttleFailSafeComboBox->setVisible(true);
......
#include "FlightModeConfig.h"
FlightModeConfig::FlightModeConfig(QWidget *parent) : QWidget(parent)
FlightModeConfig::FlightModeConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
connect(ui.savePushButton,SIGNAL(clicked()),this,SLOT(saveButtonClicked()));
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(setActiveUAS(UASInterface*)));
}
FlightModeConfig::~FlightModeConfig()
{
}
void FlightModeConfig::setActiveUAS(UASInterface *uas)
void FlightModeConfig::activeUASSet(UASInterface *uas)
{
if (!uas) return;
if (m_uas)
{
disconnect(m_uas,SIGNAL(modeChanged(int,QString,QString)),this,SLOT(modeChanged(int,QString,QString)));
disconnect(m_uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanged(int,float)));
}
m_uas = uas;
AP2ConfigWidget::activeUASSet(uas);
if (!uas) return;
connect(m_uas,SIGNAL(modeChanged(int,QString,QString)),this,SLOT(modeChanged(int,QString,QString)));
connect(m_uas,SIGNAL(parameterChanged(int,int,QString,QVariant)),this,SLOT(parameterChanged(int,int,QString,QVariant)));
connect(m_uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanged(int,float)));
QStringList itemlist;
if (m_uas->getSystemType() == MAV_TYPE_FIXED_WING)
......
......@@ -5,8 +5,9 @@
#include "ui_FlightModeConfig.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "AP2ConfigWidget.h"
class FlightModeConfig : public QWidget
class FlightModeConfig : public AP2ConfigWidget
{
Q_OBJECT
......@@ -14,7 +15,7 @@ public:
explicit FlightModeConfig(QWidget *parent = 0);
~FlightModeConfig();
private slots:
void setActiveUAS(UASInterface *uas);
void activeUASSet(UASInterface *uas);
void saveButtonClicked();
void modeChanged(int sysId, QString status, QString description);
void remoteControlChannelRawChanged(int chan,float val);
......
......@@ -32,9 +32,8 @@ This file is part of the QGROUNDCONTROL project
#include "FrameTypeConfig.h"
FrameTypeConfig::FrameTypeConfig(QWidget *parent) : QWidget(parent)
FrameTypeConfig::FrameTypeConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
m_uas=0;
ui.setupUi(this);
//Disable until we get a FRAME parameter.
......@@ -45,23 +44,11 @@ FrameTypeConfig::FrameTypeConfig(QWidget *parent) : QWidget(parent)
connect(ui.plusRadioButton,SIGNAL(clicked()),this,SLOT(plusFrameSelected()));
connect(ui.xRadioButton,SIGNAL(clicked()),this,SLOT(xFrameSelected()));
connect(ui.vRadioButton,SIGNAL(clicked()),this,SLOT(vFrameSelected()));
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
activeUASSet(UASManager::instance()->getActiveUAS());
}
FrameTypeConfig::~FrameTypeConfig()
{
}
void FrameTypeConfig::activeUASSet(UASInterface *uas)
{
if (!uas) return;
if (!m_uas)
{
disconnect(m_uas,SIGNAL(parameterChanged(int,int,QString,QVariant)),this,SLOT(parameterChanged(int,int,QString,QVariant)));
}
m_uas = uas;
connect(m_uas,SIGNAL(parameterChanged(int,int,QString,QVariant)),this,SLOT(parameterChanged(int,int,QString,QVariant)));
}
void FrameTypeConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (parameterName == "FRAME")
......
......@@ -37,7 +37,8 @@ This file is part of the QGROUNDCONTROL project
#include "UASInterface.h"
#include "UASManager.h"
#include "QGCUASParamManager.h"
class FrameTypeConfig : public QWidget
#include "AP2ConfigWidget.h"
class FrameTypeConfig : public AP2ConfigWidget
{
Q_OBJECT
......@@ -45,7 +46,6 @@ public:
explicit FrameTypeConfig(QWidget *parent = 0);
~FrameTypeConfig();
private slots:
void activeUASSet(UASInterface *uas);
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
void xFrameSelected();
void plusFrameSelected();
......
......@@ -14,7 +14,7 @@ void OsdConfig::enableButtonClicked()
{
if (!m_uas)
{
QMessageBox::information(0,tr("Error"),tr("Please connect to a MAV before attempting to set configuration"));
showNullMAVErrorMessageBox();
return;
}
m_uas->getParamManager()->setParameter(1,"SR0_EXT_STAT",2);
......
......@@ -32,15 +32,12 @@ This file is part of the QGROUNDCONTROL project
#include "RadioCalibrationConfig.h"
#include <QMessageBox>
RadioCalibrationConfig::RadioCalibrationConfig(QWidget *parent) : QWidget(parent)
RadioCalibrationConfig::RadioCalibrationConfig(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
connect(ui.calibrateButton,SIGNAL(clicked()),this,SLOT(calibrateButtonClicked()));
m_uas = 0;
m_calibrationEnabled = false;
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
setActiveUAS(UASManager::instance()->getActiveUAS());
ui.rollWidget->setMin(800);
ui.rollWidget->setMax(2200);
ui.pitchWidget->setMin(800);
......@@ -79,20 +76,18 @@ RadioCalibrationConfig::RadioCalibrationConfig(QWidget *parent) : QWidget(parent
RadioCalibrationConfig::~RadioCalibrationConfig()
{
}
void RadioCalibrationConfig::setActiveUAS(UASInterface *uas)
void RadioCalibrationConfig::activeUASSet(UASInterface *uas)
{
if (uas==NULL) return;
if (m_uas)
{
// Disconnect old system
disconnect(m_uas, SIGNAL(remoteControlChannelRawChanged(int,float)), this,SLOT(remoteControlChannelRawChanged(int,float)));
disconnect(m_uas, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,SLOT(parameterChanged(int,int,QString,QVariant)));
}
m_uas = uas;
AP2ConfigWidget::activeUASSet(uas);
if (!uas)
{
return;
}
connect(m_uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanged(int,float)));
connect(m_uas,SIGNAL(parameterChanged(int,int,QString,QVariant)),this,SLOT(parameterChanged(int,int,QString,QVariant)));
}
void RadioCalibrationConfig::remoteControlChannelRawChanged(int chan,float val)
{
......
......@@ -39,7 +39,8 @@ This file is part of the QGROUNDCONTROL project
#include "ui_RadioCalibrationConfig.h"
#include "UASManager.h"
#include "UASInterface.h"
class RadioCalibrationConfig : public QWidget
#include "AP2ConfigWidget.h"
class RadioCalibrationConfig : public AP2ConfigWidget
{
Q_OBJECT
......@@ -50,7 +51,7 @@ protected:
void showEvent(QShowEvent *event);
void hideEvent(QHideEvent *event);
private slots:
void setActiveUAS(UASInterface *uas);
void activeUASSet(UASInterface *uas);
void remoteControlChannelRawChanged(int chan,float val);
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
void guiUpdateTimerTick();
......
......@@ -7,13 +7,6 @@ StandardParamConfig::StandardParamConfig(QWidget *parent) : AP2ConfigWidget(pare
StandardParamConfig::~StandardParamConfig()
{
}
void StandardParamConfig::activeUASSet(UASInterface *uas)
{
AP2ConfigWidget::activeUASSet(uas);
}
void StandardParamConfig::addRange(QString title,QString description,QString param,double min,double max)
{
ParamWidget *widget = new ParamWidget(ui.scrollAreaWidgetContents);
......
......@@ -18,7 +18,6 @@ private slots:
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
private:
QMap<QString,ParamWidget*> paramToWidgetMap;
void activeUASSet(UASInterface *uas);
Ui::StandardParamConfig ui;
};
......
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