mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-18 03:52:11 +01:00
Refractured the Airframe config widget.
Corrected some language mistakes.
This commit is contained in:
parent
79404ab80e
commit
b9f1532598
@ -23,7 +23,7 @@
|
|||||||
<attribute name="title">
|
<attribute name="title">
|
||||||
<string>Mixer Settings</string>
|
<string>Mixer Settings</string>
|
||||||
</attribute>
|
</attribute>
|
||||||
<layout class="QVBoxLayout" name="verticalLayout_2" stretch="0,0,0,0">
|
<layout class="QVBoxLayout" name="verticalLayout_2" stretch="0,0,0">
|
||||||
<property name="margin">
|
<property name="margin">
|
||||||
<number>5</number>
|
<number>5</number>
|
||||||
</property>
|
</property>
|
||||||
@ -74,7 +74,7 @@
|
|||||||
<item>
|
<item>
|
||||||
<widget class="QStackedWidget" name="airframesWidget">
|
<widget class="QStackedWidget" name="airframesWidget">
|
||||||
<property name="currentIndex">
|
<property name="currentIndex">
|
||||||
<number>3</number>
|
<number>1</number>
|
||||||
</property>
|
</property>
|
||||||
<widget class="QWidget" name="fixedWing">
|
<widget class="QWidget" name="fixedWing">
|
||||||
<property name="enabled">
|
<property name="enabled">
|
||||||
@ -1731,75 +1731,6 @@ Typical value is 50% for + or X configuration on quads.</string>
|
|||||||
</widget>
|
</widget>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item>
|
|
||||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
|
||||||
<item>
|
|
||||||
<spacer name="horizontalSpacer">
|
|
||||||
<property name="orientation">
|
|
||||||
<enum>Qt::Horizontal</enum>
|
|
||||||
</property>
|
|
||||||
<property name="sizeHint" stdset="0">
|
|
||||||
<size>
|
|
||||||
<width>40</width>
|
|
||||||
<height>20</height>
|
|
||||||
</size>
|
|
||||||
</property>
|
|
||||||
</spacer>
|
|
||||||
</item>
|
|
||||||
<item>
|
|
||||||
<widget class="QPushButton" name="airframeHelp">
|
|
||||||
<property name="sizePolicy">
|
|
||||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
|
||||||
<horstretch>0</horstretch>
|
|
||||||
<verstretch>0</verstretch>
|
|
||||||
</sizepolicy>
|
|
||||||
</property>
|
|
||||||
<property name="maximumSize">
|
|
||||||
<size>
|
|
||||||
<width>32</width>
|
|
||||||
<height>32</height>
|
|
||||||
</size>
|
|
||||||
</property>
|
|
||||||
<property name="text">
|
|
||||||
<string/>
|
|
||||||
</property>
|
|
||||||
<property name="icon">
|
|
||||||
<iconset resource="../coreplugin/core.qrc">
|
|
||||||
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
|
|
||||||
</property>
|
|
||||||
<property name="iconSize">
|
|
||||||
<size>
|
|
||||||
<width>32</width>
|
|
||||||
<height>32</height>
|
|
||||||
</size>
|
|
||||||
</property>
|
|
||||||
<property name="flat">
|
|
||||||
<bool>true</bool>
|
|
||||||
</property>
|
|
||||||
</widget>
|
|
||||||
</item>
|
|
||||||
<item>
|
|
||||||
<widget class="QPushButton" name="saveAircraftToRAM">
|
|
||||||
<property name="toolTip">
|
|
||||||
<string>Send to board, but don't save permanently (flash or SD).</string>
|
|
||||||
</property>
|
|
||||||
<property name="text">
|
|
||||||
<string>Apply</string>
|
|
||||||
</property>
|
|
||||||
</widget>
|
|
||||||
</item>
|
|
||||||
<item>
|
|
||||||
<widget class="QPushButton" name="saveAircraftToSD">
|
|
||||||
<property name="toolTip">
|
|
||||||
<string>Applies and Saves all settings to flash or SD depending on board.</string>
|
|
||||||
</property>
|
|
||||||
<property name="text">
|
|
||||||
<string>Save</string>
|
|
||||||
</property>
|
|
||||||
</widget>
|
|
||||||
</item>
|
|
||||||
</layout>
|
|
||||||
</item>
|
|
||||||
</layout>
|
</layout>
|
||||||
</widget>
|
</widget>
|
||||||
<widget class="QWidget" name="tab">
|
<widget class="QWidget" name="tab">
|
||||||
@ -1808,7 +1739,7 @@ Typical value is 50% for + or X configuration on quads.</string>
|
|||||||
</attribute>
|
</attribute>
|
||||||
<layout class="QVBoxLayout" name="verticalLayout_25">
|
<layout class="QVBoxLayout" name="verticalLayout_25">
|
||||||
<item>
|
<item>
|
||||||
<layout class="QVBoxLayout" name="verticalLayout_11" stretch="0,1,0,0,0,0">
|
<layout class="QVBoxLayout" name="verticalLayout_11" stretch="0,1,0,0,0">
|
||||||
<item>
|
<item>
|
||||||
<layout class="QHBoxLayout" name="horizontalLayout_24">
|
<layout class="QHBoxLayout" name="horizontalLayout_24">
|
||||||
<item>
|
<item>
|
||||||
@ -2106,10 +2037,16 @@ p, li { white-space: pre-wrap; }
|
|||||||
</property>
|
</property>
|
||||||
</spacer>
|
</spacer>
|
||||||
</item>
|
</item>
|
||||||
|
</layout>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</widget>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
<item>
|
<item>
|
||||||
<layout class="QHBoxLayout" name="horizontalLayout_21">
|
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||||
<item>
|
<item>
|
||||||
<spacer name="horizontalSpacer_14">
|
<spacer name="horizontalSpacer">
|
||||||
<property name="orientation">
|
<property name="orientation">
|
||||||
<enum>Qt::Horizontal</enum>
|
<enum>Qt::Horizontal</enum>
|
||||||
</property>
|
</property>
|
||||||
@ -2122,7 +2059,39 @@ p, li { white-space: pre-wrap; }
|
|||||||
</spacer>
|
</spacer>
|
||||||
</item>
|
</item>
|
||||||
<item>
|
<item>
|
||||||
<widget class="QPushButton" name="ffApply">
|
<widget class="QPushButton" name="airframeHelp">
|
||||||
|
<property name="sizePolicy">
|
||||||
|
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||||
|
<horstretch>0</horstretch>
|
||||||
|
<verstretch>0</verstretch>
|
||||||
|
</sizepolicy>
|
||||||
|
</property>
|
||||||
|
<property name="maximumSize">
|
||||||
|
<size>
|
||||||
|
<width>32</width>
|
||||||
|
<height>32</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="text">
|
||||||
|
<string/>
|
||||||
|
</property>
|
||||||
|
<property name="icon">
|
||||||
|
<iconset resource="../coreplugin/core.qrc">
|
||||||
|
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
|
||||||
|
</property>
|
||||||
|
<property name="iconSize">
|
||||||
|
<size>
|
||||||
|
<width>32</width>
|
||||||
|
<height>32</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="flat">
|
||||||
|
<bool>true</bool>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QPushButton" name="saveAircraftToRAM">
|
||||||
<property name="toolTip">
|
<property name="toolTip">
|
||||||
<string>Send to board, but don't save permanently (flash or SD).</string>
|
<string>Send to board, but don't save permanently (flash or SD).</string>
|
||||||
</property>
|
</property>
|
||||||
@ -2132,7 +2101,7 @@ p, li { white-space: pre-wrap; }
|
|||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item>
|
<item>
|
||||||
<widget class="QPushButton" name="ffSave">
|
<widget class="QPushButton" name="saveAircraftToSD">
|
||||||
<property name="toolTip">
|
<property name="toolTip">
|
||||||
<string>Applies and Saves all settings to flash or SD depending on board.</string>
|
<string>Applies and Saves all settings to flash or SD depending on board.</string>
|
||||||
</property>
|
</property>
|
||||||
@ -2144,12 +2113,6 @@ p, li { white-space: pre-wrap; }
|
|||||||
</layout>
|
</layout>
|
||||||
</item>
|
</item>
|
||||||
</layout>
|
</layout>
|
||||||
</item>
|
|
||||||
</layout>
|
|
||||||
</widget>
|
|
||||||
</widget>
|
|
||||||
</item>
|
|
||||||
</layout>
|
|
||||||
</widget>
|
</widget>
|
||||||
<customwidgets>
|
<customwidgets>
|
||||||
<customwidget>
|
<customwidget>
|
||||||
|
@ -64,7 +64,7 @@
|
|||||||
<item row="1" column="0">
|
<item row="1" column="0">
|
||||||
<widget class="QLabel" name="label_5">
|
<widget class="QLabel" name="label_5">
|
||||||
<property name="text">
|
<property name="text">
|
||||||
<string>Flexiport</string>
|
<string>FlexiPort</string>
|
||||||
</property>
|
</property>
|
||||||
<property name="alignment">
|
<property name="alignment">
|
||||||
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
|
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
|
||||||
@ -124,6 +124,25 @@
|
|||||||
</item>
|
</item>
|
||||||
</layout>
|
</layout>
|
||||||
</item>
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="problems">
|
||||||
|
<property name="font">
|
||||||
|
<font>
|
||||||
|
<weight>75</weight>
|
||||||
|
<bold>true</bold>
|
||||||
|
</font>
|
||||||
|
</property>
|
||||||
|
<property name="text">
|
||||||
|
<string/>
|
||||||
|
</property>
|
||||||
|
<property name="textFormat">
|
||||||
|
<enum>Qt::AutoText</enum>
|
||||||
|
</property>
|
||||||
|
<property name="wordWrap">
|
||||||
|
<bool>true</bool>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
<item>
|
<item>
|
||||||
<spacer name="verticalSpacer">
|
<spacer name="verticalSpacer">
|
||||||
<property name="orientation">
|
<property name="orientation">
|
||||||
@ -140,15 +159,9 @@
|
|||||||
<item>
|
<item>
|
||||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||||
<item>
|
<item>
|
||||||
<widget class="QLabel" name="problems">
|
<widget class="QLabel" name="label_6">
|
||||||
<property name="text">
|
<property name="text">
|
||||||
<string/>
|
<string>Changes on this page require an Hw reboot to be applied</string>
|
||||||
</property>
|
|
||||||
<property name="textFormat">
|
|
||||||
<enum>Qt::AutoText</enum>
|
|
||||||
</property>
|
|
||||||
<property name="wordWrap">
|
|
||||||
<bool>true</bool>
|
|
||||||
</property>
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
|
@ -39,10 +39,10 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
|||||||
m_telemetry = new Ui_CC_HW_Widget();
|
m_telemetry = new Ui_CC_HW_Widget();
|
||||||
m_telemetry->setupUi(this);
|
m_telemetry->setupUi(this);
|
||||||
setupButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
|
setupButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
|
||||||
addObjectToWidget("TelemetrySettings","Speed",m_telemetry->telemetrySpeed);
|
addUAVObjectToWidgetRelation("TelemetrySettings","Speed",m_telemetry->telemetrySpeed);
|
||||||
addObjectToWidget("HwSettings","CC_FlexiPort",m_telemetry->cbFlexi);
|
addUAVObjectToWidgetRelation("HwSettings","CC_FlexiPort",m_telemetry->cbFlexi);
|
||||||
addObjectToWidget("HwSettings","CC_MainPort",m_telemetry->cbTele);
|
addUAVObjectToWidgetRelation("HwSettings","CC_MainPort",m_telemetry->cbTele);
|
||||||
addObjectToWidget("ManualControlSettings","InputMode",m_telemetry->receiverType);
|
addUAVObjectToWidgetRelation("ManualControlSettings","InputMode",m_telemetry->receiverType);
|
||||||
enableControls(false);
|
enableControls(false);
|
||||||
populateWidgets();
|
populateWidgets();
|
||||||
refreshWidgetsValues();
|
refreshWidgetsValues();
|
||||||
@ -59,26 +59,27 @@ void ConfigCCHWWidget::refreshValues()
|
|||||||
|
|
||||||
void ConfigCCHWWidget::widgetsContentsChanged()
|
void ConfigCCHWWidget::widgetsContentsChanged()
|
||||||
{
|
{
|
||||||
|
ConfigTaskWidget::widgetsContentsChanged();
|
||||||
enableControls(false);
|
enableControls(false);
|
||||||
if((m_telemetry->cbFlexi->currentText()==m_telemetry->cbTele->currentText()) && m_telemetry->cbTele->currentText()!="Disabled")
|
if((m_telemetry->cbFlexi->currentText()==m_telemetry->cbTele->currentText()) && m_telemetry->cbTele->currentText()!="Disabled")
|
||||||
{
|
{
|
||||||
m_telemetry->problems->setText("Warning-You have configured the main port and the flexi port for the same function, this is currently not suported");
|
m_telemetry->problems->setText("Warning: you have configured the MainPort and the FlexiPort for the same function, this is currently not suported");
|
||||||
}
|
}
|
||||||
else if((m_telemetry->cbTele->currentText()=="Spektrum" ||m_telemetry->cbFlexi->currentText()=="Spektrum") && m_telemetry->receiverType->currentText()!="Spektrum")
|
else if((m_telemetry->cbTele->currentText()=="Spektrum" ||m_telemetry->cbFlexi->currentText()=="Spektrum") && m_telemetry->receiverType->currentText()!="Spektrum")
|
||||||
{
|
{
|
||||||
m_telemetry->problems->setText("Warning-You have at least one port configured as 'Spektrum' however thats not your selected input type");
|
m_telemetry->problems->setText("Warning: you have at least one port configured as 'Spektrum' however that is not your selected input type");
|
||||||
}
|
}
|
||||||
else if(m_telemetry->cbTele->currentText()=="S.Bus" && m_telemetry->receiverType->currentText()!="S.Bus")
|
else if(m_telemetry->cbTele->currentText()=="S.Bus" && m_telemetry->receiverType->currentText()!="S.Bus")
|
||||||
{
|
{
|
||||||
m_telemetry->problems->setText("Warning-You have at least one port configured as 'S.Bus' however thats not your selected input type");
|
m_telemetry->problems->setText("Warning: you have at least one port configured as 'S.Bus' however that is not your selected input type");
|
||||||
}
|
}
|
||||||
else if(m_telemetry->cbTele->currentText()!="S.Bus" && m_telemetry->receiverType->currentText()=="S.Bus")
|
else if(m_telemetry->cbTele->currentText()!="S.Bus" && m_telemetry->receiverType->currentText()=="S.Bus")
|
||||||
{
|
{
|
||||||
m_telemetry->problems->setText("Warning-You have at selected 'S.Bus' as your input type however you have no port configured for that protocol");
|
m_telemetry->problems->setText("Warning: you have selected 'S.Bus' as your input type however you have no port configured for that protocol");
|
||||||
}
|
}
|
||||||
else if((m_telemetry->cbTele->currentText()!="Spektrum" && m_telemetry->cbFlexi->currentText()!="Spektrum") && m_telemetry->receiverType->currentText()=="Spektrum")
|
else if((m_telemetry->cbTele->currentText()!="Spektrum" && m_telemetry->cbFlexi->currentText()!="Spektrum") && m_telemetry->receiverType->currentText()=="Spektrum")
|
||||||
{
|
{
|
||||||
m_telemetry->problems->setText("Warning-You have at selected 'Spektrum' as your input type however you have no port configured for that protocol");
|
m_telemetry->problems->setText("Warning: you have at selected 'Spektrum' as your input type however you have no port configured for that protocol");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
@ -40,7 +40,7 @@ ConfigProHWWidget::ConfigProHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
|||||||
m_telemetry->setupUi(this);
|
m_telemetry->setupUi(this);
|
||||||
|
|
||||||
setupButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
|
setupButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
|
||||||
addObjectToWidget("TelemetrySettings","Speed",m_telemetry->telemetrySpeed);
|
addUAVObjectToWidgetRelation("TelemetrySettings","Speed",m_telemetry->telemetrySpeed);
|
||||||
enableControls(false);
|
enableControls(false);
|
||||||
populateWidgets();
|
populateWidgets();
|
||||||
refreshWidgetsValues();
|
refreshWidgetsValues();
|
||||||
|
@ -91,6 +91,32 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p
|
|||||||
m_aircraft = new Ui_AircraftWidget();
|
m_aircraft = new Ui_AircraftWidget();
|
||||||
m_aircraft->setupUi(this);
|
m_aircraft->setupUi(this);
|
||||||
|
|
||||||
|
setupButtons(m_aircraft->saveAircraftToRAM,m_aircraft->saveAircraftToSD);
|
||||||
|
addWidget(m_aircraft->customMixerTable);
|
||||||
|
addWidget(m_aircraft->customThrottle2Curve);
|
||||||
|
addWidget(m_aircraft->customThrottle1Curve);
|
||||||
|
addWidget(m_aircraft->multiThrottleCurve);
|
||||||
|
addWidget(m_aircraft->fixedWingThrottle);
|
||||||
|
addWidget(m_aircraft->fixedWingType);
|
||||||
|
addWidget(m_aircraft->feedForwardSlider);
|
||||||
|
addWidget(m_aircraft->accelTime);
|
||||||
|
addWidget(m_aircraft->decelTime);
|
||||||
|
addWidget(m_aircraft->maxAccelSlider);
|
||||||
|
addWidget(m_aircraft->multirotorFrameType);
|
||||||
|
addWidget(m_aircraft->multiMotor1);
|
||||||
|
addWidget(m_aircraft->multiMotor2);
|
||||||
|
addWidget(m_aircraft->multiMotor3);
|
||||||
|
addWidget(m_aircraft->multiMotor4);
|
||||||
|
addWidget(m_aircraft->multiMotor5);
|
||||||
|
addWidget(m_aircraft->multiMotor6);
|
||||||
|
addWidget(m_aircraft->multiMotor7);
|
||||||
|
addWidget(m_aircraft->multiMotor8);
|
||||||
|
addWidget(m_aircraft->triYawChannel);
|
||||||
|
addUAVObject("SystemSettings");
|
||||||
|
addUAVObject("MixerSettings");
|
||||||
|
addUAVObject("ActuatorSettings");
|
||||||
|
|
||||||
|
|
||||||
ffTuningInProgress = false;
|
ffTuningInProgress = false;
|
||||||
ffTuningPhase = false;
|
ffTuningPhase = false;
|
||||||
|
|
||||||
@ -164,11 +190,6 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p
|
|||||||
m_aircraft->customMixerTable->setItemDelegateForRow(i, sbd);
|
m_aircraft->customMixerTable->setItemDelegateForRow(i, sbd);
|
||||||
}
|
}
|
||||||
|
|
||||||
connect(m_aircraft->saveAircraftToSD, SIGNAL(clicked()), this, SLOT(saveAircraftUpdate()));
|
|
||||||
connect(m_aircraft->saveAircraftToRAM, SIGNAL(clicked()), this, SLOT(sendAircraftUpdate()));
|
|
||||||
|
|
||||||
connect(m_aircraft->ffSave, SIGNAL(clicked()), this, SLOT(saveAircraftUpdate()));
|
|
||||||
connect(m_aircraft->ffApply, SIGNAL(clicked()), this, SLOT(sendAircraftUpdate()));
|
|
||||||
connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString)));
|
connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString)));
|
||||||
connect(m_aircraft->multirotorFrameType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString)));
|
connect(m_aircraft->multirotorFrameType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString)));
|
||||||
connect(m_aircraft->aircraftType, SIGNAL(currentIndexChanged(int)), this, SLOT(switchAirframeType(int)));
|
connect(m_aircraft->aircraftType, SIGNAL(currentIndexChanged(int)), this, SLOT(switchAirframeType(int)));
|
||||||
@ -191,17 +212,8 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p
|
|||||||
connect(m_aircraft->ffTestBox3, SIGNAL(clicked(bool)), this, SLOT(enableFFTest()));
|
connect(m_aircraft->ffTestBox3, SIGNAL(clicked(bool)), this, SLOT(enableFFTest()));
|
||||||
|
|
||||||
enableControls(false);
|
enableControls(false);
|
||||||
refreshValues();
|
refreshWidgetsValues();
|
||||||
connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect()));
|
|
||||||
connect(parent, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect()));
|
|
||||||
|
|
||||||
// Register for ManualControlSettings changes:
|
|
||||||
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
|
|
||||||
connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues()));
|
|
||||||
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
|
||||||
connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues()));
|
|
||||||
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
|
|
||||||
connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues()));
|
|
||||||
|
|
||||||
// Connect the help button
|
// Connect the help button
|
||||||
connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||||
@ -213,18 +225,6 @@ ConfigAirframeWidget::~ConfigAirframeWidget()
|
|||||||
// Do nothing
|
// Do nothing
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
|
||||||
Enable or disable controls depending on whether we're ronnected or not
|
|
||||||
*/
|
|
||||||
void ConfigAirframeWidget::enableControls(bool enable)
|
|
||||||
{
|
|
||||||
//m_aircraft->saveAircraftToRAM->setEnabled(enable);
|
|
||||||
m_aircraft->saveAircraftToSD->setEnabled(enable);
|
|
||||||
//m_aircraft->ffApply->setEnabled(enable);
|
|
||||||
m_aircraft->ffSave->setEnabled(enable);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
Slot for switching the airframe type. We do it explicitely
|
Slot for switching the airframe type. We do it explicitely
|
||||||
rather than a signal in the UI, because we want to force a fitInView of the quad shapes.
|
rather than a signal in the UI, because we want to force a fitInView of the quad shapes.
|
||||||
@ -460,7 +460,7 @@ void ConfigAirframeWidget::updateCustomThrottle2CurveValue(QList<double> list, d
|
|||||||
/**
|
/**
|
||||||
Refreshes the current value of the SystemSettings which holds the aircraft type
|
Refreshes the current value of the SystemSettings which holds the aircraft type
|
||||||
*/
|
*/
|
||||||
void ConfigAirframeWidget::refreshValues()
|
void ConfigAirframeWidget::refreshWidgetsValues()
|
||||||
{
|
{
|
||||||
// Get the Airframe type from the system settings:
|
// Get the Airframe type from the system settings:
|
||||||
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
|
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
|
||||||
@ -665,11 +665,14 @@ void ConfigAirframeWidget::refreshValues()
|
|||||||
val = floor(-field->getDouble(i)/1.27);
|
val = floor(-field->getDouble(i)/1.27);
|
||||||
m_aircraft->mrYawMixLevel->setValue(val);
|
m_aircraft->mrYawMixLevel->setValue(val);
|
||||||
eng = m_aircraft->multiMotor2->currentIndex()-1;
|
eng = m_aircraft->multiMotor2->currentIndex()-1;
|
||||||
|
if(eng>-1)
|
||||||
|
{
|
||||||
field = obj->getField(mixerVectors.at(eng));
|
field = obj->getField(mixerVectors.at(eng));
|
||||||
i = field->getElementNames().indexOf("Roll");
|
i = field->getElementNames().indexOf("Roll");
|
||||||
val = floor(1-field->getDouble(i)/1.27);
|
val = floor(1-field->getDouble(i)/1.27);
|
||||||
m_aircraft->mrRollMixLevel->setValue(val);
|
m_aircraft->mrRollMixLevel->setValue(val);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
} else if (frameType == "HexaX") {
|
} else if (frameType == "HexaX") {
|
||||||
// Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW
|
// Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW
|
||||||
field = obj->getField(QString("VTOLMotorNE"));
|
field = obj->getField(QString("VTOLMotorNE"));
|
||||||
@ -1817,8 +1820,9 @@ void ConfigAirframeWidget::updateCustomAirframeUI()
|
|||||||
we call additional methods for specific frames, so that we do not have a code
|
we call additional methods for specific frames, so that we do not have a code
|
||||||
that is too heavy.
|
that is too heavy.
|
||||||
*/
|
*/
|
||||||
void ConfigAirframeWidget::sendAircraftUpdate()
|
void ConfigAirframeWidget::updateObjectsFromWidgets()
|
||||||
{
|
{
|
||||||
|
qDebug()<<"updateObjectsFromWidgets";
|
||||||
QString airframeType = "Custom";
|
QString airframeType = "Custom";
|
||||||
if (m_aircraft->aircraftType->currentText() == "Fixed Wing") {
|
if (m_aircraft->aircraftType->currentText() == "Fixed Wing") {
|
||||||
// Save the curve (common to all Fixed wing frames)
|
// Save the curve (common to all Fixed wing frames)
|
||||||
@ -2123,31 +2127,9 @@ void ConfigAirframeWidget::sendAircraftUpdate()
|
|||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
|
||||||
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
|
|
||||||
obj->updated();
|
|
||||||
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
|
||||||
obj->updated();
|
|
||||||
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
|
|
||||||
UAVObjectField* field = obj->getField(QString("AirframeType"));
|
UAVObjectField* field = obj->getField(QString("AirframeType"));
|
||||||
field->setValue(airframeType);
|
field->setValue(airframeType);
|
||||||
obj->updated();
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
Send airframe type to the board and request saving to SD card
|
|
||||||
*/
|
|
||||||
void ConfigAirframeWidget::saveAircraftUpdate()
|
|
||||||
{
|
|
||||||
// Send update so that the latest value is saved
|
|
||||||
sendAircraftUpdate();
|
|
||||||
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
|
|
||||||
Q_ASSERT(obj);
|
|
||||||
saveObjectToSD(obj);
|
|
||||||
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
|
|
||||||
saveObjectToSD(obj);
|
|
||||||
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
|
|
||||||
saveObjectToSD(obj);
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -58,7 +58,6 @@ private:
|
|||||||
void updateCustomAirframeUI();
|
void updateCustomAirframeUI();
|
||||||
bool setupMixer(double mixerFactors[8][3]);
|
bool setupMixer(double mixerFactors[8][3]);
|
||||||
void setupMotors(QList<QString> motorList);
|
void setupMotors(QList<QString> motorList);
|
||||||
virtual void enableControls(bool enable);
|
|
||||||
|
|
||||||
void resetField(UAVObjectField * field);
|
void resetField(UAVObjectField * field);
|
||||||
void resetMixer (MixerCurveWidget *mixer, int numElements, double maxvalue);
|
void resetMixer (MixerCurveWidget *mixer, int numElements, double maxvalue);
|
||||||
@ -74,9 +73,9 @@ private:
|
|||||||
UAVObject::Metadata accInitialData;
|
UAVObject::Metadata accInitialData;
|
||||||
|
|
||||||
private slots:
|
private slots:
|
||||||
virtual void refreshValues();
|
virtual void refreshWidgetsValues();
|
||||||
void sendAircraftUpdate();
|
void updateObjectsFromWidgets();
|
||||||
void saveAircraftUpdate();
|
// void saveAircraftUpdate();
|
||||||
void setupAirframeUI(QString type);
|
void setupAirframeUI(QString type);
|
||||||
void toggleAileron2(int index);
|
void toggleAileron2(int index);
|
||||||
void toggleElevator2(int index);
|
void toggleElevator2(int index);
|
||||||
|
@ -28,30 +28,68 @@
|
|||||||
#include <QtGui/QWidget>
|
#include <QtGui/QWidget>
|
||||||
|
|
||||||
|
|
||||||
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),smartsave(NULL)
|
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),smartsave(NULL),dirty(false)
|
||||||
{
|
{
|
||||||
pm = ExtensionSystem::PluginManager::instance();
|
pm = ExtensionSystem::PluginManager::instance();
|
||||||
objManager = pm->getObject<UAVObjectManager>();
|
objManager = pm->getObject<UAVObjectManager>();
|
||||||
connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect()));
|
connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect()));
|
||||||
connect(parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect()));
|
connect(parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect()));
|
||||||
}
|
}
|
||||||
void ConfigTaskWidget::addObjectToWidget(QString object, QString field, QWidget * widget)
|
void ConfigTaskWidget::addWidget(QWidget * widget)
|
||||||
{
|
{
|
||||||
UAVObject *obj = objManager->getObject(QString(object));
|
addUAVObjectToWidgetRelation("","",widget);
|
||||||
|
}
|
||||||
|
void ConfigTaskWidget::addUAVObject(QString objectName)
|
||||||
|
{
|
||||||
|
addUAVObjectToWidgetRelation(objectName,"",NULL);
|
||||||
|
}
|
||||||
|
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget)
|
||||||
|
{
|
||||||
|
UAVObject *obj=NULL;
|
||||||
|
UAVObjectField *_field=NULL;
|
||||||
|
if(!object.isEmpty())
|
||||||
|
obj = objManager->getObject(QString(object));
|
||||||
connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
|
connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
|
||||||
//smartsave->addObject(obj);
|
//smartsave->addObject(obj);
|
||||||
UAVObjectField *_field = obj->getField(QString(field));
|
if(!field.isEmpty() && obj)
|
||||||
|
_field = obj->getField(QString(field));
|
||||||
objectToWidget * ow=new objectToWidget();
|
objectToWidget * ow=new objectToWidget();
|
||||||
ow->field=_field;
|
ow->field=_field;
|
||||||
ow->object=obj;
|
ow->object=obj;
|
||||||
ow->widget=widget;
|
ow->widget=widget;
|
||||||
objOfInterest.append(ow);
|
objOfInterest.append(ow);
|
||||||
|
if(obj)
|
||||||
smartsave->addObject(obj);
|
smartsave->addObject(obj);
|
||||||
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
if(widget==NULL)
|
||||||
|
{
|
||||||
|
// do nothing
|
||||||
|
}
|
||||||
|
else if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
||||||
{
|
{
|
||||||
connect(cb,SIGNAL(currentIndexChanged(int)),this,SLOT(widgetsContentsChanged()));
|
connect(cb,SIGNAL(currentIndexChanged(int)),this,SLOT(widgetsContentsChanged()));
|
||||||
}
|
}
|
||||||
|
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
||||||
|
{
|
||||||
|
connect(cb,SIGNAL(sliderMoved(int)),this,SLOT(widgetsContentsChanged()));
|
||||||
}
|
}
|
||||||
|
else if(MixerCurveWidget * cb=qobject_cast<MixerCurveWidget *>(widget))
|
||||||
|
{
|
||||||
|
connect(cb,SIGNAL(curveUpdated(QList<double>,double)),this,SLOT(widgetsContentsChanged()));
|
||||||
|
}
|
||||||
|
else if(QTableWidget * cb=qobject_cast<QTableWidget *>(widget))
|
||||||
|
{
|
||||||
|
connect(cb,SIGNAL(cellChanged(int,int)),this,SLOT(widgetsContentsChanged()));
|
||||||
|
}
|
||||||
|
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
||||||
|
{
|
||||||
|
connect(cb,SIGNAL(valueChanged(int)),this,SLOT(widgetsContentsChanged()));
|
||||||
|
}
|
||||||
|
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
||||||
|
{
|
||||||
|
connect(cb,SIGNAL(valueChanged(double)),this,SLOT(widgetsContentsChanged()));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
ConfigTaskWidget::~ConfigTaskWidget()
|
ConfigTaskWidget::~ConfigTaskWidget()
|
||||||
{
|
{
|
||||||
@ -101,7 +139,11 @@ void ConfigTaskWidget::populateWidgets()
|
|||||||
{
|
{
|
||||||
foreach(objectToWidget * ow,objOfInterest)
|
foreach(objectToWidget * ow,objOfInterest)
|
||||||
{
|
{
|
||||||
if(QComboBox * cb=qobject_cast<QComboBox *>(ow->widget))
|
if(ow->object==NULL || ow->field==NULL)
|
||||||
|
{
|
||||||
|
// do nothing
|
||||||
|
}
|
||||||
|
else if(QComboBox * cb=qobject_cast<QComboBox *>(ow->widget))
|
||||||
{
|
{
|
||||||
cb->addItems(ow->field->getOptions());
|
cb->addItems(ow->field->getOptions());
|
||||||
cb->setCurrentIndex(cb->findText(ow->field->getValue().toString()));
|
cb->setCurrentIndex(cb->findText(ow->field->getValue().toString()));
|
||||||
@ -111,13 +153,18 @@ void ConfigTaskWidget::populateWidgets()
|
|||||||
cb->setText(ow->field->getValue().toString());
|
cb->setText(ow->field->getValue().toString());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
dirty=false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::refreshWidgetsValues()
|
void ConfigTaskWidget::refreshWidgetsValues()
|
||||||
{
|
{
|
||||||
foreach(objectToWidget * ow,objOfInterest)
|
foreach(objectToWidget * ow,objOfInterest)
|
||||||
{
|
{
|
||||||
if(QComboBox * cb=qobject_cast<QComboBox *>(ow->widget))
|
if(ow->object==NULL || ow->field==NULL)
|
||||||
|
{
|
||||||
|
//do nothing
|
||||||
|
}
|
||||||
|
else if(QComboBox * cb=qobject_cast<QComboBox *>(ow->widget))
|
||||||
{
|
{
|
||||||
cb->setCurrentIndex(cb->findText(ow->field->getValue().toString()));
|
cb->setCurrentIndex(cb->findText(ow->field->getValue().toString()));
|
||||||
}
|
}
|
||||||
@ -132,7 +179,11 @@ void ConfigTaskWidget::updateObjectsFromWidgets()
|
|||||||
{
|
{
|
||||||
foreach(objectToWidget * ow,objOfInterest)
|
foreach(objectToWidget * ow,objOfInterest)
|
||||||
{
|
{
|
||||||
if(QComboBox * cb=qobject_cast<QComboBox *>(ow->widget))
|
if(ow->object==NULL || ow->field==NULL)
|
||||||
|
{
|
||||||
|
//do nothing
|
||||||
|
}
|
||||||
|
else if(QComboBox * cb=qobject_cast<QComboBox *>(ow->widget))
|
||||||
{
|
{
|
||||||
ow->field->setValue(cb->currentText());
|
ow->field->setValue(cb->currentText());
|
||||||
}
|
}
|
||||||
@ -147,6 +198,9 @@ void ConfigTaskWidget::setupButtons(QPushButton *update, QPushButton *save)
|
|||||||
{
|
{
|
||||||
smartsave=new smartSaveButton(update,save);
|
smartsave=new smartSaveButton(update,save);
|
||||||
connect(smartsave, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets()));
|
connect(smartsave, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets()));
|
||||||
|
connect(smartsave,SIGNAL(saveSuccessfull()),this,SLOT(clearDirty()));
|
||||||
|
connect(smartsave,SIGNAL(beginOp()),this,SLOT(disableObjUpdates()));
|
||||||
|
connect(smartsave,SIGNAL(endOp()),this,SLOT(enableObjUpdates()));
|
||||||
}
|
}
|
||||||
|
|
||||||
void ConfigTaskWidget::enableControls(bool enable)
|
void ConfigTaskWidget::enableControls(bool enable)
|
||||||
@ -157,8 +211,45 @@ void ConfigTaskWidget::enableControls(bool enable)
|
|||||||
|
|
||||||
void ConfigTaskWidget::widgetsContentsChanged()
|
void ConfigTaskWidget::widgetsContentsChanged()
|
||||||
{
|
{
|
||||||
|
dirty=true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void ConfigTaskWidget::clearDirty()
|
||||||
|
{
|
||||||
|
dirty=false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool ConfigTaskWidget::isDirty()
|
||||||
|
{
|
||||||
|
return dirty;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ConfigTaskWidget::refreshValues()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void ConfigTaskWidget::disableObjUpdates()
|
||||||
|
{
|
||||||
|
foreach(objectToWidget * obj,objOfInterest)
|
||||||
|
{
|
||||||
|
if(obj->object)
|
||||||
|
disconnect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void ConfigTaskWidget::enableObjUpdates()
|
||||||
|
{
|
||||||
|
foreach(objectToWidget * obj,objOfInterest)
|
||||||
|
{
|
||||||
|
if(obj->object)
|
||||||
|
connect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -37,6 +37,10 @@
|
|||||||
#include <QList>
|
#include <QList>
|
||||||
#include <QLabel>
|
#include <QLabel>
|
||||||
#include "smartsavebutton.h"
|
#include "smartsavebutton.h"
|
||||||
|
#include "mixercurvewidget.h"
|
||||||
|
#include <QTableWidget>
|
||||||
|
#include <QDoubleSpinBox>
|
||||||
|
#include <QSpinBox>
|
||||||
class ConfigTaskWidget: public QWidget
|
class ConfigTaskWidget: public QWidget
|
||||||
{
|
{
|
||||||
Q_OBJECT
|
Q_OBJECT
|
||||||
@ -54,21 +58,28 @@ public:
|
|||||||
void saveObjectToSD(UAVObject *obj);
|
void saveObjectToSD(UAVObject *obj);
|
||||||
UAVObjectManager* getObjectManager();
|
UAVObjectManager* getObjectManager();
|
||||||
static double listMean(QList<double> list);
|
static double listMean(QList<double> list);
|
||||||
void addObjectToWidget(QString object,QString field,QWidget * widget);
|
void addUAVObject(QString objectName);
|
||||||
|
void addWidget(QWidget * widget);
|
||||||
|
void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget);
|
||||||
void setupButtons(QPushButton * update,QPushButton * save);
|
void setupButtons(QPushButton * update,QPushButton * save);
|
||||||
|
bool isDirty();
|
||||||
public slots:
|
public slots:
|
||||||
void onAutopilotDisconnect();
|
void onAutopilotDisconnect();
|
||||||
void onAutopilotConnect();
|
void onAutopilotConnect();
|
||||||
|
|
||||||
private slots:
|
private slots:
|
||||||
virtual void refreshValues()=0;
|
virtual void refreshValues();
|
||||||
virtual void updateObjectsFromWidgets();
|
virtual void updateObjectsFromWidgets();
|
||||||
private:
|
private:
|
||||||
QList <objectToWidget*> objOfInterest;
|
QList <objectToWidget*> objOfInterest;
|
||||||
ExtensionSystem::PluginManager *pm;
|
ExtensionSystem::PluginManager *pm;
|
||||||
UAVObjectManager *objManager;
|
UAVObjectManager *objManager;
|
||||||
smartSaveButton *smartsave;
|
smartSaveButton *smartsave;
|
||||||
|
bool dirty;
|
||||||
protected slots:
|
protected slots:
|
||||||
|
virtual void disableObjUpdates();
|
||||||
|
virtual void enableObjUpdates();
|
||||||
|
virtual void clearDirty();
|
||||||
virtual void widgetsContentsChanged();
|
virtual void widgetsContentsChanged();
|
||||||
virtual void populateWidgets();
|
virtual void populateWidgets();
|
||||||
virtual void refreshWidgetsValues();
|
virtual void refreshWidgetsValues();
|
||||||
|
@ -8,6 +8,7 @@ smartSaveButton::smartSaveButton(QPushButton * update, QPushButton * save):bupda
|
|||||||
}
|
}
|
||||||
void smartSaveButton::processClick()
|
void smartSaveButton::processClick()
|
||||||
{
|
{
|
||||||
|
emit beginOp();
|
||||||
bool save=false;
|
bool save=false;
|
||||||
QPushButton *button=bupdate;
|
QPushButton *button=bupdate;
|
||||||
if(sender()==bsave)
|
if(sender()==bsave)
|
||||||
@ -23,6 +24,7 @@ void smartSaveButton::processClick()
|
|||||||
bool error=false;
|
bool error=false;
|
||||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||||
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
|
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||||
|
qDebug()<<"smartbutton:save";
|
||||||
foreach(UAVObject * obj,objects)
|
foreach(UAVObject * obj,objects)
|
||||||
{
|
{
|
||||||
up_result=false;
|
up_result=false;
|
||||||
@ -73,11 +75,13 @@ void smartSaveButton::processClick()
|
|||||||
if(!error)
|
if(!error)
|
||||||
{
|
{
|
||||||
button->setIcon(QIcon(":/uploader/images/dialog-apply.svg"));
|
button->setIcon(QIcon(":/uploader/images/dialog-apply.svg"));
|
||||||
|
emit saveSuccessfull();
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
button->setIcon(QIcon(":/uploader/images/process-stop.svg"));
|
button->setIcon(QIcon(":/uploader/images/process-stop.svg"));
|
||||||
}
|
}
|
||||||
|
emit endOp();
|
||||||
}
|
}
|
||||||
|
|
||||||
void smartSaveButton::setObjects(QList<UAVObject *> list)
|
void smartSaveButton::setObjects(QList<UAVObject *> list)
|
||||||
|
@ -10,6 +10,7 @@
|
|||||||
#include <QEventLoop>
|
#include <QEventLoop>
|
||||||
#include "uavobjectutilmanager.h"
|
#include "uavobjectutilmanager.h"
|
||||||
#include <QObject>
|
#include <QObject>
|
||||||
|
#include <QDebug>
|
||||||
class smartSaveButton:public QObject
|
class smartSaveButton:public QObject
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
@ -21,6 +22,9 @@ public:
|
|||||||
void clearObjects();
|
void clearObjects();
|
||||||
signals:
|
signals:
|
||||||
void preProcessOperations();
|
void preProcessOperations();
|
||||||
|
void saveSuccessfull();
|
||||||
|
void beginOp();
|
||||||
|
void endOp();
|
||||||
private slots:
|
private slots:
|
||||||
void processClick();
|
void processClick();
|
||||||
void transaction_finished(UAVObject* obj, bool result);
|
void transaction_finished(UAVObject* obj, bool result);
|
||||||
|
Loading…
x
Reference in New Issue
Block a user