1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-20 10:54:14 +01:00

WIP configtaskwidget enhancements.

This commit is contained in:
zedamota 2012-02-02 16:22:40 +00:00
parent e1d471dc63
commit 4c1e33b0b3
16 changed files with 475 additions and 407 deletions

View File

@ -40,7 +40,7 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_telemetry = new Ui_CC_HW_Widget();
m_telemetry->setupUi(this);
setupButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
addApplySaveButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
addUAVObjectToWidgetRelation("HwSettings","CC_FlexiPort",m_telemetry->cbFlexi);
addUAVObjectToWidgetRelation("HwSettings","CC_MainPort",m_telemetry->cbTele);
addUAVObjectToWidgetRelation("HwSettings","CC_RcvrPort",m_telemetry->cbRcvr);

View File

@ -39,7 +39,7 @@ ConfigProHWWidget::ConfigProHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
m_telemetry = new Ui_PRO_HW_Widget();
m_telemetry->setupUi(this);
setupButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
addApplySaveButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
addUAVObjectToWidgetRelation("HwSettings","TelemetrySpeed",m_telemetry->telemetrySpeed);
enableControls(false);
populateWidgets();

View File

@ -95,7 +95,7 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p
m_aircraft = new Ui_AircraftWidget();
m_aircraft->setupUi(this);
setupButtons(m_aircraft->saveAircraftToRAM,m_aircraft->saveAircraftToSD);
addApplySaveButtons(m_aircraft->saveAircraftToRAM,m_aircraft->saveAircraftToSD);
addUAVObject("SystemSettings");
addUAVObject("MixerSettings");
@ -2179,7 +2179,6 @@ void ConfigAirframeWidget::addToDirtyMonitor()
addWidget(m_aircraft->elevonSlider1);
addWidget(m_aircraft->elevonSlider2);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmType);
addWidget(m_aircraft->widget_3->m_ccpm->TabObject);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmTailChannel);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmEngineChannel);
addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoWChannel);

View File

@ -42,7 +42,7 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
connect(ui->zeroBias,SIGNAL(clicked()),this,SLOT(startAccelCalibration()));
setupButtons(ui->applyButton,ui->saveButton);
addApplySaveButtons(ui->applyButton,ui->saveButton);
addUAVObject("AttitudeSettings");
// Connect the help button

View File

@ -54,10 +54,10 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent)
m_config = new Ui_InputWidget();
m_config->setupUi(this);
setupButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD);
addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD);
unsigned int index=0;
foreach(QString name,manualSettingsObj->getFields().at(0)->getElementNames())
foreach(QString name,manualSettingsObj->getField("ChannelNumber")->getElementNames())
{
Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM);
inputChannelForm * inp=new inputChannelForm(this,index==0);
@ -1095,7 +1095,7 @@ void ConfigInputWidget::invertControls()
QCheckBox * cb=qobject_cast<QCheckBox *>(wd);
if(cb)
{
int index=manualSettingsObj->getFields().at(0)->getElementNames().indexOf(cb->text());
int index=manualSettingsObj->getField("ChannelNumber")->getElementNames().indexOf(cb->text());
if((cb->isChecked() && (manualSettingsData.ChannelMax[index]>manualSettingsData.ChannelMin[index])) ||
(!cb->isChecked() && (manualSettingsData.ChannelMax[index]<manualSettingsData.ChannelMin[index])))
{

View File

@ -50,13 +50,13 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
m_config->setupUi(this);
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
setupButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
addUAVObject("ActuatorSettings");
UAVSettingsImportExportFactory * importexportplugin = pm->getObject<UAVSettingsImportExportFactory>();
connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(stopTests()));
setupButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
addApplySaveButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD);
addUAVObject("ActuatorSettings");
// NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10.

View File

@ -34,286 +34,26 @@
#include <QtGui/QPushButton>
#include <QDesktopServices>
#include <QUrl>
#include <QList>
ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
stabSettings = StabilizationSettings::GetInstance(getObjectManager());
m_stabilization = new Ui_StabilizationWidget();
m_stabilization->setupUi(this);
QList<int> * rateGroup=new QList<int>();
rateGroup->append(0);
addApplySaveButtons(m_stabilization->saveStabilizationToRAM,m_stabilization->saveStabilizationToSD);
addUAVObjectToWidgetRelation("StabilizationSettings","RollRatePID",m_stabilization->rateRollKp,"Kp",1,false,rateGroup);
setupButtons(m_stabilization->saveStabilizationToRAM,m_stabilization->saveStabilizationToSD);
addUAVObject("StabilizationSettings");
refreshWidgetsValues();
// Create a timer to regularly send the object update in case
// we want realtime updates.
connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateObjectsFromWidgets()));
connect(m_stabilization->realTimeUpdates, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdateToggle(bool)));
// Connect the updates of the stab values
connect(m_stabilization->rateRollKp, SIGNAL(valueChanged(double)), this, SLOT(updateRateRollKP(double)));
connect(m_stabilization->rateRollKi, SIGNAL(valueChanged(double)), this, SLOT(updateRateRollKI(double)));
connect(m_stabilization->rateRollILimit, SIGNAL(valueChanged(double)), this, SLOT(updateRateRollILimit(double)));
connect(m_stabilization->ratePitchKp, SIGNAL(valueChanged(double)), this, SLOT(updateRatePitchKP(double)));
connect(m_stabilization->ratePitchKi, SIGNAL(valueChanged(double)), this, SLOT(updateRatePitchKI(double)));
connect(m_stabilization->ratePitchILimit, SIGNAL(valueChanged(double)), this, SLOT(updateRatePitchILimit(double)));
connect(m_stabilization->rollKp, SIGNAL(valueChanged(double)), this, SLOT(updateRollKP(double)));
connect(m_stabilization->rollKi, SIGNAL(valueChanged(double)), this, SLOT(updateRollKI(double)));
connect(m_stabilization->rollILimit, SIGNAL(valueChanged(double)), this, SLOT(updateRollILimit(double)));
connect(m_stabilization->pitchKp, SIGNAL(valueChanged(double)), this, SLOT(updatePitchKP(double)));
connect(m_stabilization->pitchKi, SIGNAL(valueChanged(double)), this, SLOT(updatePitchKI(double)));
connect(m_stabilization->pitchILimit, SIGNAL(valueChanged(double)), this, SLOT(updatePitchILimit(double)));
// Connect the help button
connect(m_stabilization->stabilizationHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
addWidget(m_stabilization->rateRollKp);
addWidget(m_stabilization->rateRollKi);
addWidget(m_stabilization->rateRollILimit);
addWidget(m_stabilization->ratePitchKp);
addWidget(m_stabilization->ratePitchKi);
addWidget(m_stabilization->ratePitchILimit);
addWidget(m_stabilization->rateYawKp);
addWidget(m_stabilization->rateYawKi);
addWidget(m_stabilization->rateYawILimit);
addWidget(m_stabilization->rollKp);
addWidget(m_stabilization->rollKi);
addWidget(m_stabilization->rollILimit);
addWidget(m_stabilization->yawILimit);
addWidget(m_stabilization->yawKi);
addWidget(m_stabilization->yawKp);
addWidget(m_stabilization->pitchKp);
addWidget(m_stabilization->pitchKi);
addWidget(m_stabilization->pitchILimit);
addWidget(m_stabilization->rollMax);
addWidget(m_stabilization->pitchMax);
addWidget(m_stabilization->yawMax);
addWidget(m_stabilization->manualRoll);
addWidget(m_stabilization->manualPitch);
addWidget(m_stabilization->manualYaw);
addWidget(m_stabilization->maximumRoll);
addWidget(m_stabilization->maximumPitch);
addWidget(m_stabilization->maximumYaw);
addWidget(m_stabilization->lowThrottleZeroIntegral);
addDefaultButton(m_stabilization->defaultButton,0);
addReloadButton(m_stabilization->reloadButton,0);
addWidgetToDefaultReloadGroups(m_stabilization->rateRollKp,rateGroup);
}
ConfigStabilizationWidget::~ConfigStabilizationWidget()
{
// Do nothing
}
void ConfigStabilizationWidget::updateRateRollKP(double val)
{
if (m_stabilization->linkRateRP->isChecked()) {
m_stabilization->ratePitchKp->setValue(val);
}
}
void ConfigStabilizationWidget::updateRateRollKI(double val)
{
if (m_stabilization->linkRateRP->isChecked()) {
m_stabilization->ratePitchKi->setValue(val);
}
}
void ConfigStabilizationWidget::updateRateRollILimit(double val)
{
if (m_stabilization->linkRateRP->isChecked()) {
m_stabilization->ratePitchILimit->setValue(val);
}
}
void ConfigStabilizationWidget::updateRatePitchKP(double val)
{
if (m_stabilization->linkRateRP->isChecked()) {
m_stabilization->rateRollKp->setValue(val);
}
}
void ConfigStabilizationWidget::updateRatePitchKI(double val)
{
if (m_stabilization->linkRateRP->isChecked()) {
m_stabilization->rateRollKi->setValue(val);
}
}
void ConfigStabilizationWidget::updateRatePitchILimit(double val)
{
if (m_stabilization->linkRateRP->isChecked()) {
m_stabilization->rateRollILimit->setValue(val);
}
}
void ConfigStabilizationWidget::updateRollKP(double val)
{
if (m_stabilization->linkAttitudeRP->isChecked()) {
m_stabilization->pitchKp->setValue(val);
}
}
void ConfigStabilizationWidget::updateRollKI(double val)
{
if (m_stabilization->linkAttitudeRP->isChecked()) {
m_stabilization->pitchKi->setValue(val);
}
}
void ConfigStabilizationWidget::updateRollILimit(double val)
{
if (m_stabilization->linkAttitudeRP->isChecked()) {
m_stabilization->pitchILimit->setValue(val);
}
}
void ConfigStabilizationWidget::updatePitchKP(double val)
{
if (m_stabilization->linkAttitudeRP->isChecked()) {
m_stabilization->rollKp->setValue(val);
}
}
void ConfigStabilizationWidget::updatePitchKI(double val)
{
if (m_stabilization->linkAttitudeRP->isChecked()) {
m_stabilization->rollKi->setValue(val);
}
}
void ConfigStabilizationWidget::updatePitchILimit(double val)
{
if (m_stabilization->linkAttitudeRP->isChecked()) {
m_stabilization->rollILimit->setValue(val);
}
}
/*******************************
* Stabilization Settings
*****************************/
/**
Request stabilization settings from the board
*/
void ConfigStabilizationWidget::refreshWidgetsValues()
{
bool dirty=isDirty();
// Not needed anymore as this slot is only called whenever we get
// a signal that the object was just updated
// stabSettings->requestUpdate();
StabilizationSettings::DataFields stabData = stabSettings->getData();
// Now fill in all the fields, this is fairly tedious:
m_stabilization->rateRollKp->setValue(stabData.RollRatePID[StabilizationSettings::ROLLRATEPID_KP]);
m_stabilization->rateRollKi->setValue(stabData.RollRatePID[StabilizationSettings::ROLLRATEPID_KI]);
m_stabilization->rateRollILimit->setValue(stabData.RollRatePID[StabilizationSettings::ROLLRATEPID_ILIMIT]);
m_stabilization->ratePitchKp->setValue(stabData.PitchRatePID[StabilizationSettings::PITCHRATEPID_KP]);
m_stabilization->ratePitchKi->setValue(stabData.PitchRatePID[StabilizationSettings::PITCHRATEPID_KI]);
m_stabilization->ratePitchILimit->setValue(stabData.PitchRatePID[StabilizationSettings::PITCHRATEPID_ILIMIT]);
m_stabilization->rateYawKp->setValue(stabData.YawRatePID[StabilizationSettings::YAWRATEPID_KP]);
m_stabilization->rateYawKi->setValue(stabData.YawRatePID[StabilizationSettings::YAWRATEPID_KI]);
m_stabilization->rateYawILimit->setValue(stabData.YawRatePID[StabilizationSettings::YAWRATEPID_ILIMIT]);
m_stabilization->rollKp->setValue(stabData.RollPI[StabilizationSettings::ROLLPI_KP]);
m_stabilization->rollKi->setValue(stabData.RollPI[StabilizationSettings::ROLLPI_KI]);
m_stabilization->rollILimit->setValue(stabData.RollPI[StabilizationSettings::ROLLPI_ILIMIT]);
m_stabilization->pitchKp->setValue(stabData.PitchPI[StabilizationSettings::PITCHPI_KP]);
m_stabilization->pitchKi->setValue(stabData.PitchPI[StabilizationSettings::PITCHPI_KI]);
m_stabilization->pitchILimit->setValue(stabData.PitchPI[StabilizationSettings::PITCHPI_ILIMIT]);
m_stabilization->yawKp->setValue(stabData.YawPI[StabilizationSettings::YAWPI_KP]);
m_stabilization->yawKi->setValue(stabData.YawPI[StabilizationSettings::YAWPI_KI]);
m_stabilization->yawILimit->setValue(stabData.YawPI[StabilizationSettings::YAWPI_ILIMIT]);
m_stabilization->rollMax->setValue(stabData.RollMax);
m_stabilization->pitchMax->setValue(stabData.PitchMax);
m_stabilization->yawMax->setValue(stabData.YawMax);
m_stabilization->manualRoll->setValue(stabData.ManualRate[StabilizationSettings::MANUALRATE_ROLL]);
m_stabilization->manualPitch->setValue(stabData.ManualRate[StabilizationSettings::MANUALRATE_PITCH]);
m_stabilization->manualYaw->setValue(stabData.ManualRate[StabilizationSettings::MANUALRATE_YAW]);
m_stabilization->maximumRoll->setValue(stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_ROLL]);
m_stabilization->maximumPitch->setValue(stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_PITCH]);
m_stabilization->maximumYaw->setValue(stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_YAW]);
m_stabilization->lowThrottleZeroIntegral->setChecked(stabData.LowThrottleZeroIntegral==StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_TRUE ? true : false);
setDirty(dirty);
}
/**
Send telemetry settings to the board
*/
void ConfigStabilizationWidget::updateObjectsFromWidgets()
{
StabilizationSettings::DataFields stabData = stabSettings->getData();
stabData.RollRatePID[StabilizationSettings::ROLLRATEPID_KP] = m_stabilization->rateRollKp->value();
stabData.RollRatePID[StabilizationSettings::ROLLRATEPID_KI] = m_stabilization->rateRollKi->value();
stabData.RollRatePID[StabilizationSettings::ROLLRATEPID_ILIMIT] = m_stabilization->rateRollILimit->value();
stabData.PitchRatePID[StabilizationSettings::PITCHRATEPID_KP] = m_stabilization->ratePitchKp->value();
stabData.PitchRatePID[StabilizationSettings::PITCHRATEPID_KI] = m_stabilization->ratePitchKi->value();
stabData.PitchRatePID[StabilizationSettings::PITCHRATEPID_ILIMIT] = m_stabilization->ratePitchILimit->value();
stabData.YawRatePID[StabilizationSettings::YAWRATEPID_KP] = m_stabilization->rateYawKp->value();
stabData.YawRatePID[StabilizationSettings::YAWRATEPID_KI] = m_stabilization->rateYawKi->value();
stabData.YawRatePID[StabilizationSettings::YAWRATEPID_ILIMIT] = m_stabilization->rateYawILimit->value();
stabData.RollPI[StabilizationSettings::ROLLPI_KP] = m_stabilization->rollKp->value();
stabData.RollPI[StabilizationSettings::ROLLPI_KI] = m_stabilization->rollKi->value();
stabData.RollPI[StabilizationSettings::ROLLPI_ILIMIT] = m_stabilization->rollILimit->value();
stabData.PitchPI[StabilizationSettings::PITCHPI_KP] = m_stabilization->pitchKp->value();
stabData.PitchPI[StabilizationSettings::PITCHPI_KI] = m_stabilization->pitchKi->value();
stabData.PitchPI[StabilizationSettings::PITCHPI_ILIMIT] = m_stabilization->pitchILimit->value();
stabData.YawPI[StabilizationSettings::YAWPI_KP] = m_stabilization->yawKp->value();
stabData.YawPI[StabilizationSettings::YAWPI_KI] = m_stabilization->yawKi->value();
stabData.YawPI[StabilizationSettings::YAWPI_ILIMIT] = m_stabilization->yawILimit->value();
stabData.RollMax = m_stabilization->rollMax->value();
stabData.PitchMax = m_stabilization->pitchMax->value();
stabData.YawMax = m_stabilization->yawMax->value();
stabData.ManualRate[StabilizationSettings::MANUALRATE_ROLL] = m_stabilization->manualRoll->value();
stabData.ManualRate[StabilizationSettings::MANUALRATE_PITCH] = m_stabilization->manualPitch->value();
stabData.ManualRate[StabilizationSettings::MANUALRATE_YAW] = m_stabilization->manualYaw->value();
stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_ROLL] = m_stabilization->maximumRoll->value();
stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_PITCH] = m_stabilization->maximumPitch->value();
stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_YAW] = m_stabilization->maximumYaw->value();
stabData.LowThrottleZeroIntegral = (m_stabilization->lowThrottleZeroIntegral->isChecked() ? StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_TRUE :StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_FALSE);
stabSettings->setData(stabData); // this is atomic
}
void ConfigStabilizationWidget::realtimeUpdateToggle(bool state)
{
if (state) {
updateTimer.start(300);
} else {
updateTimer.stop();
}
}
void ConfigStabilizationWidget::openHelp()
{
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Stabilization+panel", QUrl::StrictMode) );
}

View File

@ -47,30 +47,8 @@ public:
private:
Ui_StabilizationWidget *m_stabilization;
StabilizationSettings* stabSettings;
QTimer updateTimer;
private slots:
virtual void refreshWidgetsValues();
void updateObjectsFromWidgets();
void realtimeUpdateToggle(bool);
void openHelp();
void updateRateRollKP(double);
void updateRateRollKI(double);
void updateRateRollILimit(double);
void updateRatePitchKP(double);
void updateRatePitchKI(double);
void updateRatePitchILimit(double);
void updateRollKP(double);
void updateRollKI(double);
void updateRollILimit(double);
void updatePitchKP(double);
void updatePitchKI(double);
void updatePitchILimit(double);
};
#endif // ConfigStabilizationWidget_H

View File

@ -56,8 +56,17 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
Q_ASSERT(_field);
addUAVObjectToWidgetRelation(object,field,widget,_field->getElementNames().indexOf(index));
}
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, int index,int scale)
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, float scale, bool isLimited, QList<int> *defaultReloadGroups)
{
UAVObject *obj=objManager->getObject(QString(object));
Q_ASSERT(obj);
UAVObjectField *_field;
if(!field.isEmpty() && obj)
_field = obj->getField(QString(field));
int index=_field->getElementNames().indexOf(QString(element));
addUAVObjectToWidgetRelation(object, field, widget,index,scale,isLimited,defaultReloadGroups);
}
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, int index,float scale,bool isLimited,QList<int>* defaultReloadGroups)
{
UAVObject *obj=NULL;
UAVObjectField *_field=NULL;
@ -69,7 +78,6 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*)));
connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
}
//smartsave->addObject(obj);
if(!field.isEmpty() && obj)
_field = obj->getField(QString(field));
objectToWidget * ow=new objectToWidget();
@ -80,50 +88,28 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
ow->scale=scale;
objOfInterest.append(ow);
if(obj)
smartsave->addObject((UAVDataObject*)obj);
{
if(smartsave)
{
smartsave->addObject((UAVDataObject*)obj);
emit objectAdded(obj);
}
}
if(widget==NULL)
{
// do nothing
}
else if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{
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()));
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
{
connect(cb,SIGNAL(clicked()),this,SLOT(widgetsContentsChanged()));
}
else if(QPushButton * cb=qobject_cast<QPushButton *>(widget))
{
connect(cb,SIGNAL(clicked()),this,SLOT(widgetsContentsChanged()));
}
else
connectWidgetUpdatesToSlot(widget,SLOT(widgetsContentsChanged()));
if(defaultReloadGroups)
addWidgetToDefaultReloadGroups(widget,defaultReloadGroups);
}
ConfigTaskWidget::~ConfigTaskWidget()
{
delete smartsave;
foreach(QList<objectToWidget*>* pointer,defaultReloadGroups.values())
delete pointer;
}
void ConfigTaskWidget::saveObjectToSD(UAVObject *obj)
@ -176,31 +162,12 @@ void ConfigTaskWidget::populateWidgets()
bool dirtyBack=dirty;
foreach(objectToWidget * ow,objOfInterest)
{
if(ow->object==NULL || ow->field==NULL)
if(ow->object==NULL || ow->field==NULL || ow->widget==NULL)
{
// do nothing
}
else if(QComboBox * cb=qobject_cast<QComboBox *>(ow->widget))
{
cb->addItems(ow->field->getOptions());
cb->setCurrentIndex(cb->findText(ow->field->getValue(ow->index).toString()));
}
else if(QLabel * cb=qobject_cast<QLabel *>(ow->widget))
{
cb->setText(ow->field->getValue(ow->index).toString());
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(ow->widget))
{
cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale);
}
else if(QSlider * cb=qobject_cast<QSlider *>(ow->widget))
{
cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale);
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(ow->widget))
{
cb->setChecked(ow->field->getValue(ow->index).toBool());
}
else
setWidgetFromField(ow->widget,ow->field,ow->index,ow->scale);
}
setDirty(dirtyBack);
}
@ -210,30 +177,15 @@ void ConfigTaskWidget::refreshWidgetsValues()
bool dirtyBack=dirty;
foreach(objectToWidget * ow,objOfInterest)
{
if(ow->object==NULL || ow->field==NULL)
if(ow->object==NULL || ow->field==NULL || ow->widget==NULL)
{
//do nothing
}
else if(QComboBox * cb=qobject_cast<QComboBox *>(ow->widget))
else
{
cb->setCurrentIndex(cb->findText(ow->field->getValue(ow->index).toString()));
}
else if(QLabel * cb=qobject_cast<QLabel *>(ow->widget))
{
cb->setText(ow->field->getValue(ow->index).toString());
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(ow->widget))
{
cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale);
}
else if(QSlider * cb=qobject_cast<QSlider *>(ow->widget))
{
cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale);
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(ow->widget))
{
cb->setChecked(ow->field->getValue(ow->index).toBool());
setWidgetFromField(ow->widget,ow->field,ow->index,ow->scale);
}
}
setDirty(dirtyBack);
}
@ -244,38 +196,29 @@ void ConfigTaskWidget::updateObjectsFromWidgets()
{
if(ow->object==NULL || ow->field==NULL)
{
//do nothing
}
else if(QComboBox * cb=qobject_cast<QComboBox *>(ow->widget))
{
ow->field->setValue(cb->currentText(),ow->index);
}
else if(QLabel * cb=qobject_cast<QLabel *>(ow->widget))
{
ow->field->setValue(cb->text(),ow->index);
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(ow->widget))
{
ow->field->setValue(cb->value()* ow->scale,ow->index);
}
else if(QSlider * cb=qobject_cast<QSlider *>(ow->widget))
{
ow->field->setValue(cb->value()* ow->scale,ow->index);
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(ow->widget))
{
ow->field->setValue((cb->isChecked()?"TRUE":"FALSE"),ow->index);
}
else
setFieldFromWidget(ow->widget,ow->field,ow->index,ow->scale);
}
}
void ConfigTaskWidget::setupButtons(QPushButton *update, QPushButton *save)
void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save)
{
smartsave=new smartSaveButton(update,save);
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()));
if(objOfInterest.count()>0)
{
foreach(objectToWidget * oTw,objOfInterest)
{
smartsave->addObject((UAVDataObject*)oTw->object);
emit objectAdded(oTw->object);
}
}
enableControls(false);
}
@ -333,6 +276,34 @@ void ConfigTaskWidget::objectUpdated(UAVObject *obj)
objectUpdates[obj]=true;
}
void ConfigTaskWidget::removeObject(UAVObject * obj)
{
emit objectRemoved(obj);
QList<objectToWidget*> toRemove;
foreach(objectToWidget * oTw,objOfInterest)
{
if(oTw->object==obj)
{
toRemove.append(oTw);
}
}
foreach(objectToWidget * oTw,toRemove)
{
objOfInterest.removeAll(oTw);
smartsave->removeObject((UAVDataObject*)oTw->object);
}
}
void ConfigTaskWidget::removeAllObjects()
{
foreach(objectToWidget * oTw,objOfInterest)
{
emit objectRemoved(oTw->object);
}
objOfInterest.clear();
smartsave->removeAllObjects();
}
bool ConfigTaskWidget::allObjectsUpdated()
{
bool ret=true;
@ -352,12 +323,311 @@ void ConfigTaskWidget::invalidateObjects()
}
}
bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, float scale, bool isLimited)
{
foreach(objectToWidget * oTw, objOfInterest)
{
if(oTw->object->getName()==object && oTw->field->getName()==field && oTw->index==index)
{
oTw->shadows.append(widget);
}
}
}
void ConfigTaskWidget::autoLoadWidgets()
{
QPushButton * saveButtonWidget=NULL;
QPushButton * applyButtonWidget=NULL;
foreach(QObject * widget,this->children())
{
QVariant info=widget->property("objrelation");
if(info.isValid())
{
uiRelationAutomation uiRelation;
uiRelation.buttonType=none;
foreach(QString str, info.toStringList())
{
QString prop=str.split(":").at(0);
QString value=str.split(":").at(1);
if(prop== "objname")
uiRelation.objname=value;
else if(prop== "fieldname")
uiRelation.fieldname=value;
else if(prop=="element")
uiRelation.element=value;
else if(prop== "scale")
{
if(value=="null")
uiRelation.scale=1;
else
uiRelation.scale=value.toFloat();
}
else if(prop== "ismaster")
{
if(value=="yes")
uiRelation.ismaster=true;
else
uiRelation.ismaster=false;
}
else if(prop== "haslimits")
{
if(value=="yes")
uiRelation.haslimits=true;
else
uiRelation.haslimits=false;
}
else if(prop== "button")
{
if(value=="save")
uiRelation.buttonType=save_button;
else if(value=="apply")
uiRelation.buttonType=apply_button;
else if(value=="reload")
uiRelation.buttonType=reload_button;
else if(value=="default")
uiRelation.buttonType=default_button;
}
else if(prop== "buttongroup")
{
foreach(QString s,value.split(","))
{
uiRelation.buttonGroup.append(s.toInt());
}
}
}
if(!uiRelation.buttonType==none)
{
QPushButton * button=NULL;
switch(uiRelation.buttonType)
{
case save_button:
saveButtonWidget=qobject_cast<QPushButton *>(widget);
break;
case apply_button:
applyButtonWidget=qobject_cast<QPushButton *>(widget);
break;
case default_button:
button=qobject_cast<QPushButton *>(widget);
if(button)
addDefaultButton(button,uiRelation.buttonGroup.at(0));
break;
case reload_button:
button=qobject_cast<QPushButton *>(widget);
if(button)
addReloadButton(button,uiRelation.buttonGroup.at(0));
break;
default:
break;
}
}
else if(uiRelation.ismaster)
{
QWidget * wid=qobject_cast<QWidget *>(widget);
if(wid)
addUAVObjectToWidgetRelation(uiRelation.objname,uiRelation.fieldname,wid,uiRelation.element,uiRelation.haslimits,&uiRelation.buttonGroup);
}
}
}
if(saveButtonWidget && applyButtonWidget)
addApplySaveButtons(applyButtonWidget,saveButtonWidget);
}
void ConfigTaskWidget::addWidgetToDefaultReloadGroups(QWidget *widget, QList<int> * groups)
{
foreach(objectToWidget * oTw,objOfInterest)
{
bool addOTW=false;
if(oTw->widget==widget)
addOTW=true;
else
{
foreach(QWidget * shadow, oTw->shadows)
{
if(shadow==widget)
addOTW=true;
}
}
if(addOTW)
{
foreach(int i,*groups)
{
if(defaultReloadGroups.contains(i))
{
defaultReloadGroups.value(i)->append(oTw);
}
else
{
defaultReloadGroups.insert(i,new QList<objectToWidget*>());
defaultReloadGroups.value(i)->append(oTw);
}
}
}
}
}
void ConfigTaskWidget::addDefaultButton(QPushButton *button, int buttonGroup)
{
button->setProperty("group",buttonGroup);
connect(button,SIGNAL(clicked()),this,SLOT(defaultButtonClicked()));
}
void ConfigTaskWidget::addReloadButton(QPushButton *button, int buttonGroup)
{
button->setProperty("group",buttonGroup);
connect(button,SIGNAL(clicked()),this,SLOT(reloadButtonClicked()));
}
void ConfigTaskWidget::defaultButtonClicked()
{
int group=sender()->property("group").toInt();
QList<objectToWidget*> * list=defaultReloadGroups.value(group);
foreach(objectToWidget * oTw,*list)
{
UAVDataObject * temp=((UAVDataObject*)oTw->object)->dirtyClone();
setWidgetFromField(oTw->widget,temp->getField(oTw->field->getName()),oTw->index,oTw->scale);
}
}
void ConfigTaskWidget::reloadButtonClicked()
{
int group=sender()->property("group").toInt();
QList<objectToWidget*> * list=defaultReloadGroups.value(group);
ObjectPersistence* objper = dynamic_cast<ObjectPersistence*>( getObjectManager()->getObject(ObjectPersistence::NAME) );
foreach(objectToWidget * oTw,*list)
{
if (oTw->object != NULL)
{
ObjectPersistence::DataFields data;
data.Operation = ObjectPersistence::OPERATION_LOAD;
data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT;
data.ObjectID = oTw->object->getObjID();
data.InstanceID = oTw->object->getInstID();
objper->setData(data);
objper->updated();
}
}
}
void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget * widget,const char* function)
{
if(!widget)
return;
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{
connect(cb,SIGNAL(currentIndexChanged(int)),this,function);
}
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
connect(cb,SIGNAL(sliderMoved(int)),this,function);
}
else if(MixerCurveWidget * cb=qobject_cast<MixerCurveWidget *>(widget))
{
connect(cb,SIGNAL(curveUpdated(QList<double>,double)),this,function);
}
else if(QTableWidget * cb=qobject_cast<QTableWidget *>(widget))
{
connect(cb,SIGNAL(cellChanged(int,int)),this,function);
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
connect(cb,SIGNAL(valueChanged(int)),this,function);
}
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
connect(cb,SIGNAL(valueChanged(double)),this,function);
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
{
connect(cb,SIGNAL(clicked()),this,function);
}
else if(QPushButton * cb=qobject_cast<QPushButton *>(widget))
{
connect(cb,SIGNAL(clicked()),this,function);
}
else
qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<<widget->metaObject()->className();
}
bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * field,int index,float scale)
{
if(!widget || !field)
return false;
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{
field->setValue(cb->currentText(),index);
return true;
}
else if(QLabel * cb=qobject_cast<QLabel *>(widget))
{
field->setValue(cb->text(),index);
return true;
}
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
field->setValue(cb->value()* scale,index);
return true;
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
field->setValue(cb->value()* (int)scale,index);
return true;
}
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
field->setValue(cb->value()* (int)scale,index);
return true;
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
{
field->setValue((cb->isChecked()?"TRUE":"FALSE"),index);
return true;
}
else
{
qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<<widget->metaObject()->className();
return false;
}
}
bool ConfigTaskWidget::setWidgetFromField(QWidget * widget,UAVObjectField * field,int index,float scale)
{
if(!widget || !field)
return false;
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{
if(cb->count()==0)
cb->addItems(field->getOptions());
cb->setCurrentIndex(cb->findText(field->getValue(index).toString()));
return true;
}
else if(QLabel * cb=qobject_cast<QLabel *>(widget))
{
cb->setText(field->getValue(index).toString());
return true;
}
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
cb->setValue(field->getValue(index).toDouble()/scale);
return true;
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
cb->setValue(field->getValue(index).toInt()/(int)scale);
return true;
}
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
cb->setValue(field->getValue(index).toInt()/(int)scale);
return true;
}
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
{
cb->setChecked(field->getValue(index).toBool());
return true;
}
else
{
qDebug()<<__FUNCTION__<<"widget to uavobject relation not implemented"<<widget->metaObject()->className();
return false;
}
}
/**
@}

View File

@ -55,7 +55,30 @@ public:
UAVObjectField * field;
QWidget * widget;
int index;
float scale;
bool isLimited;
QList<QWidget *> shadows;
};
struct shadows
{
QWidget * widget;
float scale;
bool isLimited;
QWidget * parent;
};
enum buttonTypeEnum {none,save_button,apply_button,reload_button,default_button};
struct uiRelationAutomation
{
QString objname;
QString fieldname;
QString element;
int scale;
bool ismaster;
bool haslimits;
buttonTypeEnum buttonType;
QList<int> buttonGroup;
};
ConfigTaskWidget(QWidget *parent = 0);
@ -65,22 +88,40 @@ public:
static double listMean(QList<double> list);
void addUAVObject(QString objectName);
void addWidget(QWidget * widget);
void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,int index=0,int scale=1);
void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,int index=0,float scale=1,bool isLimited=false,QList<int>* defaultReloadGroups=0);
void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,QString element,float scale,bool isLimited=false,QList<int>* defaultReloadGroups=0);
void addApplySaveButtons(QPushButton * update,QPushButton * save);
void addReloadButton(QPushButton * button,int buttonGroup);
void addDefaultButton(QPushButton * button,int buttonGroup);
void addWidgetToDefaultReloadGroups(QWidget * widget, QList<int> *groups);
bool addShadowWidget(QWidget * masterWidget, QWidget * shadowWidget,float shadowScale=1,bool shadowIsLimited=false);
bool addShadowWidget(QString object,QString field,QWidget * widget,int index=0,float scale=1,bool isLimited=false);
void autoLoadWidgets();
void setupButtons(QPushButton * update,QPushButton * save);
bool isDirty();
void setDirty(bool value);
void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index);
bool allObjectsUpdated();
public slots:
void onAutopilotDisconnect();
void onAutopilotConnect();
void invalidateObjects();
void removeObject(UAVObject*);
void removeAllObjects();
signals:
void objectAdded(UAVObject*);
void objectRemoved(UAVObject*);
private slots:
virtual void refreshValues();
virtual void updateObjectsFromWidgets();
void objectUpdated(UAVObject*);
void defaultButtonClicked();
void reloadButtonClicked();
private:
bool isConnected;
QStringList objectsList;
@ -89,7 +130,12 @@ private:
UAVObjectManager *objManager;
smartSaveButton *smartsave;
QMap<UAVObject *,bool> objectUpdates;
QMap<int,QList<objectToWidget*> *> defaultReloadGroups;
QList <shadows*> shadowsList;
bool dirty;
bool setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, float scale);
bool setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, float scale);
void connectWidgetUpdatesToSlot(QWidget *widget, const char *function);
protected slots:
virtual void disableObjUpdates();
virtual void enableObjUpdates();

View File

@ -101,7 +101,15 @@ void smartSaveButton::addObject(UAVDataObject * obj)
if(!objects.contains(obj))
objects.append(obj);
}
void smartSaveButton::removeObject(UAVDataObject * obj)
{
if(objects.contains(obj))
objects.removeAll(obj);
}
void smartSaveButton::removeAllObjects()
{
objects.clear();
}
void smartSaveButton::clearObjects()
{
objects.clear();

View File

@ -20,6 +20,8 @@ public:
void setObjects(QList<UAVDataObject *>);
void addObject(UAVDataObject *);
void clearObjects();
void removeObject(UAVDataObject *obj);
void removeAllObjects();
signals:
void preProcessOperations();
void saveSuccessfull();

View File

@ -747,6 +747,20 @@ automatically every 300ms, which will help for fast tuning.</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="reloadButton">
<property name="text">
<string>reload</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="defaultButton">
<property name="text">
<string>default</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveStabilizationToRAM">
<property name="text">

View File

@ -47,6 +47,7 @@ public:
Metadata getMetadata();
UAVMetaObject* getMetaObject();
virtual UAVDataObject* clone(quint32 instID = 0) = 0;
virtual UAVDataObject* dirtyClone() = 0;
private:
UAVMetaObject* mobj;

View File

@ -119,6 +119,15 @@ UAVDataObject* $(NAME)::clone(quint32 instID)
return obj;
}
/**
* Create a clone of this object only to be used to retrieve defaults
*/
UAVDataObject* $(NAME)::dirtyClone()
{
$(NAME)* obj = new $(NAME)();
return obj;
}
/**
* Static function to retrieve an instance of the object.
*/

View File

@ -64,7 +64,8 @@ $(DATAFIELDINFO)
void setData(const DataFields& data);
Metadata getDefaultMetadata();
UAVDataObject* clone(quint32 instID);
UAVDataObject* dirtyClone();
static $(NAME)* GetInstance(UAVObjectManager* objMngr, quint32 instID = 0);
private: