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