mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
Added Dado's UI.
Several scale bug fixes. Added lots of debug info, will clean later.
This commit is contained in:
parent
35c5391d53
commit
e2c6a9d58a
@ -40,7 +40,7 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
|
||||
{
|
||||
m_stabilization = new Ui_StabilizationWidget();
|
||||
m_stabilization->setupUi(this);
|
||||
QList<int> * rateGroup=new QList<int>();
|
||||
/* QList<int> * rateGroup=new QList<int>();
|
||||
rateGroup->append(0);
|
||||
addApplySaveButtons(m_stabilization->saveStabilizationToRAM,m_stabilization->saveStabilizationToSD);
|
||||
addUAVObjectToWidgetRelation("StabilizationSettings","RollRatePID",m_stabilization->rateRollKp,"Kp",1,true,rateGroup);
|
||||
@ -48,7 +48,8 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
|
||||
addDefaultButton(m_stabilization->defaultButton,0);
|
||||
addReloadButton(m_stabilization->reloadButton,0);
|
||||
addWidgetToDefaultReloadGroups(m_stabilization->rateRollKp,rateGroup);
|
||||
addShadowWidget("StabilizationSettings","RollRatePID",m_stabilization->rateRollKi,0,1,true,rateGroup);
|
||||
addShadowWidget("StabilizationSettings","RollRatePID",m_stabilization->rateRollKi,0,1,true,rateGroup);*/
|
||||
autoLoadWidgets();
|
||||
}
|
||||
|
||||
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -107,10 +107,13 @@ void UAVObjectField::limitsInitialize(const QString &limits)
|
||||
return;
|
||||
QStringList stringPerElement=limits.split(",");
|
||||
foreach (QString str, stringPerElement) {
|
||||
QStringList valuesPerElement=str.split(":");
|
||||
QString _str=str.trimmed();
|
||||
QStringList valuesPerElement=_str.split(":");
|
||||
LimitStruct lstruc;
|
||||
quint32 index=valuesPerElement.at(0).mid(1,valuesPerElement.at(0).length()-3).toULong();
|
||||
if(valuesPerElement.at(0).startsWith("%") && index<numElements)
|
||||
quint32 index=stringPerElement.indexOf(str);
|
||||
bool b1=valuesPerElement.at(0).startsWith("%");
|
||||
bool b2=(int)(index)<(int)numElements;
|
||||
if(b1 && b2)
|
||||
{
|
||||
if(valuesPerElement.at(0).right(2)=="EQ")
|
||||
lstruc.type=EQUAL;
|
||||
@ -123,10 +126,11 @@ void UAVObjectField::limitsInitialize(const QString &limits)
|
||||
else if(valuesPerElement.at(0).right(2)=="SM")
|
||||
lstruc.type=SMALLER;
|
||||
else
|
||||
qDebug()<<"limits parsing failed on UAVObjectField"<<name;
|
||||
qDebug()<<"limits parsing failed (invalid property) on UAVObjectField"<<name;
|
||||
valuesPerElement.removeAt(0);
|
||||
foreach(QString value,valuesPerElement)
|
||||
foreach(QString _value,valuesPerElement)
|
||||
{
|
||||
QString value=_value.trimmed();
|
||||
switch (type)
|
||||
{
|
||||
case INT8:
|
||||
@ -155,7 +159,12 @@ void UAVObjectField::limitsInitialize(const QString &limits)
|
||||
elementLimits.insert(index,lstruc);
|
||||
}
|
||||
else
|
||||
qDebug()<<"limits parsing failed on UAVObjectField"<<name;
|
||||
{
|
||||
if(!valuesPerElement.at(0).startsWith("%"))
|
||||
qDebug()<<"limits parsing failed (property doesn't start with %) on UAVObjectField"<<name;
|
||||
else if(index>=numElements)
|
||||
qDebug()<<"limits parsing failed (index>numelements) on UAVObjectField"<<name<<"index"<<index<<"numElements"<<numElements;
|
||||
}
|
||||
}
|
||||
}
|
||||
bool UAVObjectField::isWithinLimits(QVariant var,quint32 index)
|
||||
|
@ -56,7 +56,7 @@ 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, QString element, float scale, bool isLimited, QList<int> *defaultReloadGroups)
|
||||
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString element, double scale, bool isLimited, QList<int> *defaultReloadGroups)
|
||||
{
|
||||
UAVObject *obj=objManager->getObject(QString(object));
|
||||
Q_ASSERT(obj);
|
||||
@ -66,7 +66,7 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel
|
||||
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)
|
||||
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, int index,double scale,bool isLimited,QList<int>* defaultReloadGroups)
|
||||
{
|
||||
if(addShadowWidget(object,field,widget,index,scale,isLimited,defaultReloadGroups))
|
||||
return;
|
||||
@ -221,6 +221,13 @@ void ConfigTaskWidget::updateObjectsFromWidgets()
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::helpButtonPressed()
|
||||
{
|
||||
QString url=helpButtonList.value((QPushButton*)sender(),QString::QString());
|
||||
if(!url.isEmpty())
|
||||
QDesktopServices::openUrl( QUrl(url, QUrl::StrictMode) );
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::addApplySaveButtons(QPushButton *update, QPushButton *save)
|
||||
{
|
||||
smartsave=new smartSaveButton(update,save);
|
||||
@ -247,7 +254,7 @@ void ConfigTaskWidget::enableControls(bool enable)
|
||||
|
||||
void ConfigTaskWidget::widgetsContentsChanged()
|
||||
{
|
||||
float scale;
|
||||
double scale;
|
||||
objectToWidget * oTw= shadowsList.value((QWidget*)sender(),NULL);
|
||||
|
||||
/*
|
||||
@ -372,6 +379,13 @@ bool ConfigTaskWidget::allObjectsUpdated()
|
||||
return ret;
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::addHelpButton(QPushButton *button, QString url)
|
||||
{
|
||||
helpButtonList.insert(button,url);
|
||||
connect(button,SIGNAL(clicked()),this,SLOT(helpButtonPressed()));
|
||||
|
||||
}
|
||||
|
||||
void ConfigTaskWidget::invalidateObjects()
|
||||
{
|
||||
foreach(UAVObject *obj, objectUpdates.keys())
|
||||
@ -380,7 +394,7 @@ void ConfigTaskWidget::invalidateObjects()
|
||||
}
|
||||
}
|
||||
|
||||
bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, float scale, bool isLimited,QList<int>* defaultReloadGroups)
|
||||
bool ConfigTaskWidget::addShadowWidget(QString object, QString field, QWidget *widget, int index, double scale, bool isLimited,QList<int>* defaultReloadGroups)
|
||||
{
|
||||
foreach(objectToWidget * oTw,objOfInterest)
|
||||
{
|
||||
@ -408,13 +422,15 @@ void ConfigTaskWidget::autoLoadWidgets()
|
||||
{
|
||||
QPushButton * saveButtonWidget=NULL;
|
||||
QPushButton * applyButtonWidget=NULL;
|
||||
foreach(QObject * widget,this->children())
|
||||
foreach(QWidget * widget,this->findChildren<QWidget*>())
|
||||
{
|
||||
QVariant info=widget->property("objrelation");
|
||||
if(info.isValid())
|
||||
{
|
||||
qDebug()<<"processing autoloadwidget";
|
||||
uiRelationAutomation uiRelation;
|
||||
uiRelation.buttonType=none;
|
||||
uiRelation.scale=1;
|
||||
foreach(QString str, info.toStringList())
|
||||
{
|
||||
QString prop=str.split(":").at(0);
|
||||
@ -430,14 +446,7 @@ void ConfigTaskWidget::autoLoadWidgets()
|
||||
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;
|
||||
uiRelation.scale=value.toDouble();
|
||||
}
|
||||
else if(prop== "haslimits")
|
||||
{
|
||||
@ -456,6 +465,9 @@ void ConfigTaskWidget::autoLoadWidgets()
|
||||
uiRelation.buttonType=reload_button;
|
||||
else if(value=="default")
|
||||
uiRelation.buttonType=default_button;
|
||||
else if(value=="help")
|
||||
uiRelation.buttonType=help_button;
|
||||
|
||||
}
|
||||
else if(prop== "buttongroup")
|
||||
{
|
||||
@ -465,6 +477,8 @@ void ConfigTaskWidget::autoLoadWidgets()
|
||||
}
|
||||
|
||||
}
|
||||
else if(prop=="url")
|
||||
uiRelation.url=value;
|
||||
}
|
||||
if(!uiRelation.buttonType==none)
|
||||
{
|
||||
@ -491,11 +505,12 @@ void ConfigTaskWidget::autoLoadWidgets()
|
||||
break;
|
||||
}
|
||||
}
|
||||
else if(uiRelation.ismaster)
|
||||
else
|
||||
{
|
||||
QWidget * wid=qobject_cast<QWidget *>(widget);
|
||||
qDebug()<<"adding widget"<<(quint32)wid;
|
||||
if(wid)
|
||||
addUAVObjectToWidgetRelation(uiRelation.objname,uiRelation.fieldname,wid,uiRelation.element,uiRelation.haslimits,&uiRelation.buttonGroup);
|
||||
addUAVObjectToWidgetRelation(uiRelation.objname,uiRelation.fieldname,wid,uiRelation.element,uiRelation.scale,uiRelation.haslimits,&uiRelation.buttonGroup);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -632,7 +647,7 @@ void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget * widget,const char* f
|
||||
|
||||
}
|
||||
|
||||
bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * field,int index,float scale)
|
||||
bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * field,int index,double scale)
|
||||
{
|
||||
if(!widget || !field)
|
||||
return false;
|
||||
@ -647,7 +662,7 @@ bool ConfigTaskWidget::setFieldFromWidget(QWidget * widget,UAVObjectField * fiel
|
||||
return false;
|
||||
}
|
||||
}
|
||||
QVariant ConfigTaskWidget::getVariantFromWidget(QWidget * widget,float scale)
|
||||
QVariant ConfigTaskWidget::getVariantFromWidget(QWidget * widget,double scale)
|
||||
{
|
||||
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
||||
{
|
||||
@ -663,11 +678,11 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget * widget,float scale)
|
||||
}
|
||||
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
||||
{
|
||||
return (int)(cb->value()* (int)scale);
|
||||
return (double)(cb->value()* scale);
|
||||
}
|
||||
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
||||
{
|
||||
return(int)(cb->value()* (int)scale);
|
||||
return(double)(cb->value()* scale);
|
||||
}
|
||||
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
|
||||
{
|
||||
@ -677,7 +692,7 @@ QVariant ConfigTaskWidget::getVariantFromWidget(QWidget * widget,float scale)
|
||||
return QVariant();
|
||||
}
|
||||
|
||||
bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, float scale)
|
||||
bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, double scale)
|
||||
{
|
||||
if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
|
||||
{
|
||||
@ -691,17 +706,18 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, flo
|
||||
}
|
||||
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
||||
{
|
||||
cb->setValue(value.toDouble()/scale);
|
||||
cb->setValue((double)(value.toDouble()/scale));
|
||||
return true;
|
||||
}
|
||||
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
||||
{
|
||||
cb->setValue(value.toInt()/(int)scale);
|
||||
cb->setValue((int)(value.toDouble()/scale));
|
||||
return true;
|
||||
}
|
||||
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
||||
{
|
||||
cb->setValue(value.toInt()/(int)scale);
|
||||
cb->setValue((int)(value.toDouble()/scale));
|
||||
qDebug()<<"SETVALUE widgetfromvariant"<<value.toDouble()<<"/"<<scale<<"="<<(int)(value.toDouble()/scale)<<"object"<<(quint32)cb;
|
||||
return true;
|
||||
}
|
||||
else if(QCheckBox * cb=qobject_cast<QCheckBox *>(widget))
|
||||
@ -713,7 +729,7 @@ bool ConfigTaskWidget::setWidgetFromVariant(QWidget *widget, QVariant value, flo
|
||||
return false;
|
||||
}
|
||||
|
||||
bool ConfigTaskWidget::setWidgetFromField(QWidget * widget,UAVObjectField * field,int index,float scale,bool hasLimits)
|
||||
bool ConfigTaskWidget::setWidgetFromField(QWidget * widget,UAVObjectField * field,int index,double scale,bool hasLimits)
|
||||
{
|
||||
if(!widget || !field)
|
||||
return false;
|
||||
@ -733,7 +749,7 @@ bool ConfigTaskWidget::setWidgetFromField(QWidget * widget,UAVObjectField * fiel
|
||||
return false;
|
||||
}
|
||||
}
|
||||
void ConfigTaskWidget::checkWidgetsLimits(QWidget * widget,UAVObjectField * field,int index,bool hasLimits, QVariant value, float scale)
|
||||
void ConfigTaskWidget::checkWidgetsLimits(QWidget * widget,UAVObjectField * field,int index,bool hasLimits, QVariant value, double scale)
|
||||
{
|
||||
if(!hasLimits)
|
||||
return;
|
||||
@ -751,36 +767,36 @@ void ConfigTaskWidget::checkWidgetsLimits(QWidget * widget,UAVObjectField * fiel
|
||||
}
|
||||
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
|
||||
{
|
||||
if(value.toDouble()/scale>cb->maximum())
|
||||
if((double)(value.toDouble()/scale)>cb->maximum())
|
||||
{
|
||||
cb->setMaximum(value.toDouble()/scale);
|
||||
cb->setMaximum((double)(value.toDouble()/scale));
|
||||
}
|
||||
else if(value.toDouble()/scale<cb->minimum())
|
||||
else if((double)(value.toDouble()/scale)<cb->minimum())
|
||||
{
|
||||
cb->setMinimum(value.toDouble()/scale);
|
||||
cb->setMinimum((double)(value.toDouble()/scale));
|
||||
}
|
||||
|
||||
}
|
||||
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
||||
{
|
||||
if(value.toInt()/scale>cb->maximum())
|
||||
if((int)(value.toDouble()/scale)>cb->maximum())
|
||||
{
|
||||
cb->setMaximum(value.toInt()/scale);
|
||||
cb->setMaximum((int)(value.toDouble()/scale));
|
||||
}
|
||||
else if(value.toInt()/scale<cb->minimum())
|
||||
else if((int)(value.toDouble()/scale)<cb->minimum())
|
||||
{
|
||||
cb->setMinimum(value.toInt()/scale);
|
||||
cb->setMinimum((int)(value.toDouble()/scale));
|
||||
}
|
||||
}
|
||||
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
||||
{
|
||||
if(value.toInt()/scale>cb->maximum())
|
||||
if((int)(value.toDouble()/scale)>cb->maximum())
|
||||
{
|
||||
cb->setMaximum(value.toInt()/scale);
|
||||
cb->setMaximum((int)(value.toDouble()/scale));
|
||||
}
|
||||
else if(value.toInt()/scale<cb->minimum())
|
||||
else if((int)(value.toDouble()/scale)<cb->minimum())
|
||||
{
|
||||
cb->setMinimum(value.toInt()/scale);
|
||||
cb->setMinimum((int)(value.toDouble()/scale));
|
||||
}
|
||||
}
|
||||
|
||||
@ -803,7 +819,7 @@ void ConfigTaskWidget::checkWidgetsLimits(QWidget * widget,UAVObjectField * fiel
|
||||
}
|
||||
}
|
||||
}
|
||||
void ConfigTaskWidget::loadWidgetLimits(QWidget * widget,UAVObjectField * field,int index,bool hasLimits,float scale)
|
||||
void ConfigTaskWidget::loadWidgetLimits(QWidget * widget,UAVObjectField * field,int index,bool hasLimits,double scale)
|
||||
{
|
||||
if(!widget || !field)
|
||||
return;
|
||||
@ -828,33 +844,35 @@ void ConfigTaskWidget::loadWidgetLimits(QWidget * widget,UAVObjectField * field,
|
||||
{
|
||||
if(field->getMaxLimit(index).isValid())
|
||||
{
|
||||
cb->setMaximum(field->getMaxLimit(index).toDouble()/scale);
|
||||
cb->setMaximum((double)(field->getMaxLimit(index).toDouble()/scale));
|
||||
}
|
||||
if(field->getMinLimit(index).isValid())
|
||||
{
|
||||
cb->setMinimum(field->getMinLimit(index).toDouble()/scale);
|
||||
cb->setMinimum((double)(field->getMinLimit(index).toDouble()/scale));
|
||||
}
|
||||
}
|
||||
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
|
||||
{
|
||||
if(field->getMaxLimit(index).isValid())
|
||||
{
|
||||
cb->setMaximum((int)(field->getMaxLimit(index).toInt()/scale));
|
||||
cb->setMaximum((int)(field->getMaxLimit(index).toDouble()/scale));
|
||||
}
|
||||
if(field->getMinLimit(index).isValid())
|
||||
{
|
||||
cb->setMinimum((int)(field->getMinLimit(index).toInt()/scale));
|
||||
cb->setMinimum((int)(field->getMinLimit(index).toDouble()/scale));
|
||||
}
|
||||
}
|
||||
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
|
||||
{
|
||||
if(field->getMaxLimit(index).isValid())
|
||||
{
|
||||
cb->setMaximum((int)(field->getMaxLimit(index).toInt()/scale));
|
||||
cb->setMaximum((int)(field->getMaxLimit(index).toDouble()/scale));
|
||||
qDebug()<<"MAX="<<field->getMaxLimit(index).toDouble()<<"/"<<scale<<"="<<cb->maximum();
|
||||
}
|
||||
if(field->getMinLimit(index).isValid())
|
||||
{
|
||||
cb->setMinimum((int)(field->getMinLimit(index).toInt()/scale));
|
||||
cb->setMinimum((int)(field->getMinLimit(index).toDouble()/scale));
|
||||
qDebug()<<"MIN="<<field->getMinLimit(index).toDouble()<<"/"<<scale<<"="<<cb->minimum();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -44,6 +44,8 @@
|
||||
#include <QCheckBox>
|
||||
#include <QPushButton>
|
||||
#include "uavobjectwidgetutils_global.h"
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
|
||||
class UAVOBJECTWIDGETUTILS_EXPORT ConfigTaskWidget: public QWidget
|
||||
{
|
||||
@ -53,7 +55,7 @@ public:
|
||||
struct shadow
|
||||
{
|
||||
QWidget * widget;
|
||||
float scale;
|
||||
double scale;
|
||||
bool isLimited;
|
||||
};
|
||||
struct objectToWidget
|
||||
@ -62,19 +64,19 @@ public:
|
||||
UAVObjectField * field;
|
||||
QWidget * widget;
|
||||
int index;
|
||||
float scale;
|
||||
double scale;
|
||||
bool isLimited;
|
||||
QList<shadow *> shadowsList;
|
||||
};
|
||||
|
||||
enum buttonTypeEnum {none,save_button,apply_button,reload_button,default_button};
|
||||
enum buttonTypeEnum {none,save_button,apply_button,reload_button,default_button,help_button};
|
||||
struct uiRelationAutomation
|
||||
{
|
||||
QString objname;
|
||||
QString fieldname;
|
||||
QString element;
|
||||
int scale;
|
||||
bool ismaster;
|
||||
QString url;
|
||||
double scale;
|
||||
bool haslimits;
|
||||
buttonTypeEnum buttonType;
|
||||
QList<int> buttonGroup;
|
||||
@ -90,8 +92,8 @@ public:
|
||||
void addUAVObject(QString objectName);
|
||||
void addWidget(QWidget * widget);
|
||||
|
||||
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 addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,int index=0,double scale=1,bool isLimited=false,QList<int>* defaultReloadGroups=0);
|
||||
void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,QString element,double scale,bool isLimited=false,QList<int>* defaultReloadGroups=0);
|
||||
void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index);
|
||||
|
||||
//BUTTONS//
|
||||
@ -102,8 +104,8 @@ void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget
|
||||
|
||||
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, QList<int> *defaultReloadGroups=NULL);
|
||||
bool addShadowWidget(QWidget * masterWidget, QWidget * shadowWidget,double shadowScale=1,bool shadowIsLimited=false);
|
||||
bool addShadowWidget(QString object,QString field,QWidget * widget,int index=0,double scale=1,bool isLimited=false, QList<int> *defaultReloadGroups=NULL);
|
||||
|
||||
void autoLoadWidgets();
|
||||
|
||||
@ -111,7 +113,8 @@ void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget
|
||||
void setDirty(bool value);
|
||||
|
||||
bool allObjectsUpdated();
|
||||
|
||||
void setOutOfLimitsStyle(QString style){outOfLimitsStyle=style;}
|
||||
void addHelpButton(QPushButton * button,QString url);
|
||||
public slots:
|
||||
void onAutopilotDisconnect();
|
||||
void onAutopilotConnect();
|
||||
@ -135,13 +138,14 @@ private:
|
||||
QMap<UAVObject *,bool> objectUpdates;
|
||||
QMap<int,QList<objectToWidget*> *> defaultReloadGroups;
|
||||
QMap<QWidget *,objectToWidget*> shadowsList;
|
||||
QMap<QPushButton *,QString> helpButtonList;
|
||||
bool dirty;
|
||||
bool setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, float scale);
|
||||
bool setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, float scale, bool hasLimits);
|
||||
QVariant getVariantFromWidget(QWidget *widget, float scale);
|
||||
bool setWidgetFromVariant(QWidget *widget,QVariant value,float scale);
|
||||
bool setFieldFromWidget(QWidget *widget, UAVObjectField *field, int index, double scale);
|
||||
bool setWidgetFromField(QWidget *widget, UAVObjectField *field, int index, double scale, bool hasLimits);
|
||||
QVariant getVariantFromWidget(QWidget *widget, double scale);
|
||||
bool setWidgetFromVariant(QWidget *widget,QVariant value,double scale);
|
||||
void connectWidgetUpdatesToSlot(QWidget *widget, const char *function);
|
||||
void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, float sclale);
|
||||
void loadWidgetLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, double sclale);
|
||||
QString outOfLimitsStyle;
|
||||
protected slots:
|
||||
virtual void disableObjUpdates();
|
||||
@ -151,9 +155,10 @@ protected slots:
|
||||
virtual void populateWidgets();
|
||||
virtual void refreshWidgetsValues();
|
||||
virtual void updateObjectsFromWidgets();
|
||||
virtual void helpButtonPressed();
|
||||
protected:
|
||||
virtual void enableControls(bool enable);
|
||||
void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, float scale);
|
||||
void checkWidgetsLimits(QWidget *widget, UAVObjectField *field, int index, bool hasLimits, QVariant value, double scale);
|
||||
};
|
||||
|
||||
#endif // CONFIGTASKWIDGET_H
|
||||
|
@ -1,18 +1,18 @@
|
||||
<xml>
|
||||
<object name="StabilizationSettings" singleinstance="true" settings="true">
|
||||
<description>PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired</description>
|
||||
<field name="RollMax" units="degrees" type="uint8" elements="1" defaultvalue="55"/>
|
||||
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="55"/>
|
||||
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="35"/>
|
||||
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,150"/>
|
||||
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300"/>
|
||||
<field name="RollMax" units="degrees" type="uint8" elements="1" defaultvalue="55" limits="%BE:0:180"/>
|
||||
<field name="PitchMax" units="degrees" type="uint8" elements="1" defaultvalue="55" limits="%BE:0:180"/>
|
||||
<field name="YawMax" units="degrees" type="uint8" elements="1" defaultvalue="35" limits="%BE:0:180"/>
|
||||
<field name="ManualRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="150,150,150" limits="%BE:0:500,%BE:0:500,%BE:0:500"/>
|
||||
<field name="MaximumRate" units="degrees/sec" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="300,300,300" limits="%BE:0:500,%BE:0:500,%BE:0:500"/>
|
||||
|
||||
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.002,0,0,0.3"/>
|
||||
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.002,0,0,0.3"/>
|
||||
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0035,0.0035,0,0.3"/>
|
||||
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/>
|
||||
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/>
|
||||
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50"/>
|
||||
<field name="RollRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.002,0,0,0.3" limits="%BE:0:0.01,%BE:0:0.01,, "/>
|
||||
<field name="PitchRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.002,0,0,0.3" limits="%BE:0:0.01,%BE:0:0.01,, "/>
|
||||
<field name="YawRatePID" units="" type="float" elementnames="Kp,Ki,Kd,ILimit" defaultvalue="0.0035,0.0035,0,0.3" limits="%BE:0:0.01,%BE:0:0.01,, "/>
|
||||
<field name="RollPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50" limits="%BE:0:10,%BE:0:10,, "/>
|
||||
<field name="PitchPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50" limits="%BE:0:10,%BE:0:10,, "/>
|
||||
<field name="YawPI" units="" type="float" elementnames="Kp,Ki,ILimit" defaultvalue="2,0,50" limits="%BE:0:10,%BE:0:10,, "/>
|
||||
|
||||
<field name="GyroTau" units="" type="float" elements="1" defaultvalue="0.005"/>
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user