rule_editing.cpp
Go to the documentation of this file.
00001 #include "rule_editing.h"
00002 #include "ui_rule_editing.h"
00003 #include <QDomDocument>
00004 #include <QSettings>
00005 #include <QPlainTextEdit>
00006 #include <QTimer>
00007 #include <QMessageBox>
00008 
00009 const char* DEFAULT_RULES =
00010         "<SubstitutionRules>\n"
00011         "\n"
00012         "<RosType name=\"sensor_msgs/JointState\">\n"
00013         "  <rule pattern=\"position.#\" alias=\"name.#\" substitution=\"@/pos\" />\n"
00014         "  <rule pattern=\"velocity.#\" alias=\"name.#\" substitution=\"@/vel\" />\n"
00015         "  <rule pattern=\"effort.#\"   alias=\"name.#\" substitution=\"@/eff\" />\n"
00016         "</RosType>\n"
00017         "\n"
00018         "<RosType name=\"tf/tfMessage\">"
00019         "  <rule pattern=\"transforms.#/header\"                alias=\"transforms.#/child_frame_id\"  substitution=\"@/header\" />\n"
00020         "  <rule pattern=\"transforms.#/transform/rotation\"    alias=\"transforms.#/child_frame_id\"  substitution=\"@/rotation\" />\n"
00021         "  <rule pattern=\"transforms.#/transform/translation\" alias=\"transforms.#/child_frame_id\"  substitution=\"@/translation\" />\n"
00022         "</RosType>\n"
00023         "\n"
00024         "<RosType name=\"tf2_msgs/TFMessage\">"
00025         "  <rule pattern=\"transforms.#/header\"                alias=\"transforms.#/child_frame_id\"  substitution=\"@/header\" />\n"
00026         "  <rule pattern=\"transforms.#/transform/rotation\"    alias=\"transforms.#/child_frame_id\"  substitution=\"@/rotation\" />\n"
00027         "  <rule pattern=\"transforms.#/transform/translation\" alias=\"transforms.#/child_frame_id\"  substitution=\"@/translation\" />\n"
00028         "</RosType>\n"
00029         "\n"
00030         "<RosType name=\"pal_statistics_msgs/Statistics\">\n"
00031         "  <rule pattern=\"statistics.#/value\" alias=\"statistics.#/name\" substitution=\"@\" />\n"
00032         "</RosType>\n"
00033         "</SubstitutionRules>\n"
00034         ;
00035 
00036 XMLSyntaxHighlighter::XMLSyntaxHighlighter(QObject * parent) :
00037     QSyntaxHighlighter(parent)
00038 {
00039     setRegexes();
00040     setFormats();
00041 }
00042 
00043 XMLSyntaxHighlighter::XMLSyntaxHighlighter(QTextDocument * parent) :
00044     QSyntaxHighlighter(parent)
00045 {
00046     setRegexes();
00047     setFormats();
00048 }
00049 
00050 XMLSyntaxHighlighter::XMLSyntaxHighlighter(QTextEdit * parent) :
00051     QSyntaxHighlighter(parent)
00052 {
00053     setRegexes();
00054     setFormats();
00055 }
00056 
00057 void XMLSyntaxHighlighter::highlightBlock(const QString & text)
00058 {
00059     // Special treatment for xml element regex as we use captured text to emulate lookbehind
00060     int xmlElementIndex = _xmlElementRegex.indexIn(text);
00061     while(xmlElementIndex >= 0)
00062     {
00063         int matchedPos = _xmlElementRegex.pos(1);
00064         int matchedLength = _xmlElementRegex.cap(1).length();
00065         setFormat(matchedPos, matchedLength, _xmlElementFormat);
00066 
00067         xmlElementIndex = _xmlElementRegex.indexIn(text, matchedPos + matchedLength);
00068     }
00069 
00070     // Highlight xml keywords *after* xml elements to fix any occasional / captured into the enclosing element
00071     typedef QList<QRegExp>::const_iterator Iter;
00072     Iter xmlKeywordRegexesEnd = _xmlKeywordRegexes.end();
00073     for(Iter it = _xmlKeywordRegexes.begin(); it != xmlKeywordRegexesEnd; ++it) {
00074         const QRegExp & regex = *it;
00075         highlightByRegex(_xmlKeywordFormat, regex, text);
00076     }
00077 
00078     highlightByRegex(_xmlAttributeFormat, _xmlAttributeRegex, text);
00079     highlightByRegex(_xmlCommentFormat, _xmlCommentRegex, text);
00080     highlightByRegex(_xmlValueFormat, _xmlValueRegex, text);
00081 }
00082 
00083 void XMLSyntaxHighlighter::highlightByRegex(const QTextCharFormat & format,
00084                                             const QRegExp & regex,
00085                                             const QString & text)
00086 {
00087     int index = regex.indexIn(text);
00088     while(index >= 0)
00089     {
00090         int matchedLength = regex.matchedLength();
00091         setFormat(index, matchedLength, format);
00092         index = regex.indexIn(text, index + matchedLength);
00093     }
00094 }
00095 
00096 void XMLSyntaxHighlighter::setRegexes()
00097 {
00098     _xmlElementRegex.setPattern("<[\\s]*[/]?[\\s]*([^\\n]\\w*)(?=[\\s/>])");
00099     _xmlAttributeRegex.setPattern("\\w+(?=\\=)");
00100     _xmlValueRegex.setPattern("\"[^\\n\"]+\"(?=[\\s/>])");
00101     _xmlCommentRegex.setPattern("<!--[^\\n]*-->");
00102 
00103     _xmlKeywordRegexes = QList<QRegExp>() << QRegExp("<\\?") << QRegExp("/>")
00104                                           << QRegExp(">") << QRegExp("<") << QRegExp("</")
00105                                           << QRegExp("\\?>");
00106 }
00107 
00108 void XMLSyntaxHighlighter::setFormats()
00109 {
00110     _xmlKeywordFormat.setForeground(Qt::blue);
00111     _xmlElementFormat.setForeground(Qt::darkMagenta);
00112 
00113     _xmlAttributeFormat.setForeground(Qt::darkGreen);
00114     _xmlAttributeFormat.setFontItalic(true);
00115 
00116     _xmlValueFormat.setForeground(Qt::darkRed);
00117     _xmlCommentFormat.setForeground(Qt::gray);
00118 }
00119 
00120 RuleEditing::RuleEditing(QWidget *parent) :
00121     QDialog(parent),
00122     ui(new Ui::RuleEditing)
00123 {
00124     ui->setupUi(this);
00125 
00126     _highlighter = new XMLSyntaxHighlighter(ui->textEdit);
00127 
00128     QSettings settings;
00129     restoreGeometry(settings.value("RuleEditing.geometry").toByteArray());
00130 
00131     ui->textEdit->setPlainText( getRenamingXML() );
00132 
00133     _timer.setInterval(200);
00134     _timer.setSingleShot(false);
00135     _timer.start();
00136 
00137     const QFont fixedFont = QFontDatabase::systemFont(QFontDatabase::FixedFont);
00138 
00139     ui->textEdit->setFont(fixedFont);
00140 
00141     connect(&_timer, &QTimer::timeout, this, &RuleEditing::on_timer );
00142 }
00143 
00144 RuleEditing::~RuleEditing()
00145 {
00146     delete ui;
00147 }
00148 
00149 
00150 bool RuleEditing::isValidXml()
00151 {
00152     QString errorStr;
00153     int errorLine, errorColumn;
00154     bool valid = true;
00155 
00156     QDomDocument domDocument;
00157     QString text = ui->textEdit->toPlainText();
00158 
00159     if (!domDocument.setContent(text , true,
00160                                 &errorStr, &errorLine, &errorColumn))
00161     {
00162         ui->labelValidSyntax->setText("Invalid XML: " + errorStr);
00163         return false;
00164     }
00165     QDomElement root = domDocument.namedItem("SubstitutionRules").toElement();
00166 
00167     if( root.isNull() ){
00168         errorStr = tr("the root node should be <SubstitutionRules>");
00169         ui->labelValidSyntax->setText(tr("Invalid: ") + errorStr);
00170         return false;
00171     }
00172 
00173     for ( auto type_el = root.firstChildElement( )  ;
00174           type_el.isNull() == false;
00175           type_el = type_el.nextSiblingElement() )
00176     {
00177         if( type_el.nodeName() != "RosType")
00178         {
00179             errorStr = tr("<SubstitutionRules> must have children named <RosType>");
00180             ui->labelValidSyntax->setText(tr("Invalid: ") + errorStr);
00181             return false;
00182         }
00183         if( type_el.hasAttribute("name") == false)
00184         {
00185             errorStr = tr("node <RosType> must have the attribute [name]");
00186             ui->labelValidSyntax->setText(tr("Invalid: ") + errorStr);
00187             return false;
00188         }
00189 
00190         for ( auto rule_el = type_el.firstChildElement( )  ;
00191               rule_el.isNull() == false;
00192               rule_el = rule_el.nextSiblingElement( ) )
00193         {
00194             if( rule_el.nodeName() != "rule")
00195             {
00196                 errorStr = tr("<RosType> must have children named <rule>");
00197                 ui->labelValidSyntax->setText(tr("Invalid: ") + errorStr);
00198                 return false;
00199             }
00200             if( !rule_el.hasAttribute("pattern") ||
00201                     !rule_el.hasAttribute("alias") ||
00202                     !rule_el.hasAttribute("substitution") )
00203             {
00204                 errorStr = tr("<rule> must have the attributes 'pattern', 'alias' and 'substitution'");
00205                 ui->labelValidSyntax->setText(tr("Invalid: ") + errorStr);
00206                 return false;
00207             }
00208         }
00209     }
00210     ui->labelValidSyntax->setText(tr("Valid") + errorStr);
00211     return true;
00212 }
00213 
00214 void RuleEditing::on_pushButtonSave_pressed()
00215 {
00216     QSettings settings;
00217     settings.setValue("RuleEditing.text", ui->textEdit->toPlainText() );
00218     this->close();
00219 }
00220 
00221 void RuleEditing::closeEvent(QCloseEvent *event)
00222 {
00223     QSettings settings;
00224     settings.setValue("RuleEditing.geometry", saveGeometry());
00225     QWidget::closeEvent(event);
00226 }
00227 
00228 void RuleEditing::on_timer()
00229 {
00230     bool valid = isValidXml();
00231     ui->pushButtonSave->setEnabled(valid);
00232 }
00233 
00234 void RuleEditing::on_pushButtonCancel_pressed()
00235 {
00236     this->close();
00237 }
00238 
00239 void RuleEditing::on_pushButtonReset_pressed()
00240 {
00241     QMessageBox::StandardButton reply;
00242     reply = QMessageBox::question(0, tr("Warning"),
00243                                   tr("Do you really want to overwrite these rules\n"),
00244                                   QMessageBox::Yes | QMessageBox::No,
00245                                   QMessageBox::No );
00246     if( reply == QMessageBox::Yes )
00247     {
00248         ui->textEdit->setPlainText( DEFAULT_RULES );
00249     }
00250 }
00251 
00252 QString RuleEditing::getRenamingXML()
00253 {
00254     QSettings settings;
00255     if( settings.contains("RuleEditing.text") )
00256     {
00257         return settings.value("RuleEditing.text").toString();
00258     }
00259     else{
00260         return DEFAULT_RULES;
00261     }
00262 }
00263 
00264 RosIntrospection::SubstitutionRuleMap RuleEditing::getRenamingRules()
00265 {
00266     using namespace RosIntrospection;
00267     SubstitutionRuleMap rule_map;
00268 
00269     QDomDocument domDocument;
00270 
00271     if (!domDocument.setContent( getRenamingXML() , true))
00272     {
00273         return rule_map;
00274     }
00275     QDomElement root = domDocument.namedItem("SubstitutionRules").toElement();
00276 
00277     for ( auto type_el = root.firstChildElement("RosType")  ;
00278           type_el.isNull() == false;
00279           type_el = type_el.nextSiblingElement("RosType") )
00280     {
00281         std::string type_name = type_el.attribute("name").toStdString();
00282         std::vector<SubstitutionRule> rules_vect;
00283 
00284         for ( auto rule_el = type_el.firstChildElement("rule")  ;
00285               rule_el.isNull() == false;
00286               rule_el = rule_el.nextSiblingElement("rule") )
00287         {
00288             std::string pattern      = rule_el.attribute("pattern").toStdString();
00289             std::string substitution = rule_el.attribute("substitution").toStdString();
00290             std::string alias        = rule_el.attribute("alias").toStdString();
00291 
00292             SubstitutionRule rule( pattern.c_str(),
00293                                    alias.c_str(),
00294                                    substitution.c_str() );
00295 
00296             rules_vect.push_back( rule );
00297         }
00298         rule_map.insert( std::make_pair( ROSType(type_name), std::move( rules_vect ) ));
00299     }
00300     return rule_map;
00301 }
00302 


plotjuggler
Author(s): Davide Faconti
autogenerated on Wed Jul 3 2019 19:28:05