rule_editing.cpp
Go to the documentation of this file.
1 #include "rule_editing.h"
2 #include "ui_rule_editing.h"
3 #include <QDomDocument>
4 #include <QSettings>
5 #include <QPlainTextEdit>
6 #include <QTimer>
7 #include <QMessageBox>
8 
9 const char* DEFAULT_RULES =
10  "<SubstitutionRules>\n"
11  "\n"
12  "<RosType name=\"sensor_msgs/JointState\">\n"
13  " <rule pattern=\"position.#\" alias=\"name.#\" substitution=\"@/pos\" />\n"
14  " <rule pattern=\"velocity.#\" alias=\"name.#\" substitution=\"@/vel\" />\n"
15  " <rule pattern=\"effort.#\" alias=\"name.#\" substitution=\"@/eff\" />\n"
16  "</RosType>\n"
17  "\n"
18  "<RosType name=\"tf/tfMessage\">"
19  " <rule pattern=\"transforms.#/header\" alias=\"transforms.#/child_frame_id\" substitution=\"@/header\" />\n"
20  " <rule pattern=\"transforms.#/transform/rotation\" alias=\"transforms.#/child_frame_id\" substitution=\"@/rotation\" />\n"
21  " <rule pattern=\"transforms.#/transform/translation\" alias=\"transforms.#/child_frame_id\" substitution=\"@/translation\" />\n"
22  "</RosType>\n"
23  "\n"
24  "<RosType name=\"tf2_msgs/TFMessage\">"
25  " <rule pattern=\"transforms.#/header\" alias=\"transforms.#/child_frame_id\" substitution=\"@/header\" />\n"
26  " <rule pattern=\"transforms.#/transform/rotation\" alias=\"transforms.#/child_frame_id\" substitution=\"@/rotation\" />\n"
27  " <rule pattern=\"transforms.#/transform/translation\" alias=\"transforms.#/child_frame_id\" substitution=\"@/translation\" />\n"
28  "</RosType>\n"
29  "\n"
30  "<RosType name=\"pal_statistics_msgs/Statistics\">\n"
31  " <rule pattern=\"statistics.#/value\" alias=\"statistics.#/name\" substitution=\"@\" />\n"
32  "</RosType>\n"
33  "</SubstitutionRules>\n"
34  ;
35 
37  QSyntaxHighlighter(parent)
38 {
39  setRegexes();
40  setFormats();
41 }
42 
44  QSyntaxHighlighter(parent)
45 {
46  setRegexes();
47  setFormats();
48 }
49 
51  QSyntaxHighlighter(parent)
52 {
53  setRegexes();
54  setFormats();
55 }
56 
57 void XMLSyntaxHighlighter::highlightBlock(const QString & text)
58 {
59  // Special treatment for xml element regex as we use captured text to emulate lookbehind
60  int xmlElementIndex = _xmlElementRegex.indexIn(text);
61  while(xmlElementIndex >= 0)
62  {
63  int matchedPos = _xmlElementRegex.pos(1);
64  int matchedLength = _xmlElementRegex.cap(1).length();
65  setFormat(matchedPos, matchedLength, _xmlElementFormat);
66 
67  xmlElementIndex = _xmlElementRegex.indexIn(text, matchedPos + matchedLength);
68  }
69 
70  // Highlight xml keywords *after* xml elements to fix any occasional / captured into the enclosing element
71  typedef QList<QRegExp>::const_iterator Iter;
72  Iter xmlKeywordRegexesEnd = _xmlKeywordRegexes.end();
73  for(Iter it = _xmlKeywordRegexes.begin(); it != xmlKeywordRegexesEnd; ++it) {
74  const QRegExp & regex = *it;
75  highlightByRegex(_xmlKeywordFormat, regex, text);
76  }
77 
81 }
82 
83 void XMLSyntaxHighlighter::highlightByRegex(const QTextCharFormat & format,
84  const QRegExp & regex,
85  const QString & text)
86 {
87  int index = regex.indexIn(text);
88  while(index >= 0)
89  {
90  int matchedLength = regex.matchedLength();
91  setFormat(index, matchedLength, format);
92  index = regex.indexIn(text, index + matchedLength);
93  }
94 }
95 
97 {
98  _xmlElementRegex.setPattern("<[\\s]*[/]?[\\s]*([^\\n]\\w*)(?=[\\s/>])");
99  _xmlAttributeRegex.setPattern("\\w+(?=\\=)");
100  _xmlValueRegex.setPattern("\"[^\\n\"]+\"(?=[\\s/>])");
101  _xmlCommentRegex.setPattern("<!--[^\\n]*-->");
102 
103  _xmlKeywordRegexes = QList<QRegExp>() << QRegExp("<\\?") << QRegExp("/>")
104  << QRegExp(">") << QRegExp("<") << QRegExp("</")
105  << QRegExp("\\?>");
106 }
107 
109 {
110  _xmlKeywordFormat.setForeground(Qt::blue);
111  _xmlElementFormat.setForeground(Qt::darkMagenta);
112 
113  _xmlAttributeFormat.setForeground(Qt::darkGreen);
114  _xmlAttributeFormat.setFontItalic(true);
115 
116  _xmlValueFormat.setForeground(Qt::darkRed);
117  _xmlCommentFormat.setForeground(Qt::gray);
118 }
119 
120 RuleEditing::RuleEditing(QWidget *parent) :
121  QDialog(parent),
122  ui(new Ui::RuleEditing)
123 {
124  ui->setupUi(this);
125 
126  _highlighter = new XMLSyntaxHighlighter(ui->textEdit);
127 
128  QSettings settings;
129  restoreGeometry(settings.value("RuleEditing.geometry").toByteArray());
130 
131  ui->textEdit->setPlainText( getRenamingXML() );
132 
133  _timer.setInterval(200);
134  _timer.setSingleShot(false);
135  _timer.start();
136 
137  const QFont fixedFont = QFontDatabase::systemFont(QFontDatabase::FixedFont);
138 
139  ui->textEdit->setFont(fixedFont);
140 
141  connect(&_timer, &QTimer::timeout, this, &RuleEditing::on_timer );
142 }
143 
145 {
146  delete ui;
147 }
148 
149 
151 {
152  QString errorStr;
153  int errorLine, errorColumn;
154  bool valid = true;
155 
156  QDomDocument domDocument;
157  QString text = ui->textEdit->toPlainText();
158 
159  if (!domDocument.setContent(text , true,
160  &errorStr, &errorLine, &errorColumn))
161  {
162  ui->labelValidSyntax->setText("Invalid XML: " + errorStr);
163  return false;
164  }
165  QDomElement root = domDocument.namedItem("SubstitutionRules").toElement();
166 
167  if( root.isNull() ){
168  errorStr = tr("the root node should be <SubstitutionRules>");
169  ui->labelValidSyntax->setText(tr("Invalid: ") + errorStr);
170  return false;
171  }
172 
173  for ( auto type_el = root.firstChildElement( ) ;
174  type_el.isNull() == false;
175  type_el = type_el.nextSiblingElement() )
176  {
177  if( type_el.nodeName() != "RosType")
178  {
179  errorStr = tr("<SubstitutionRules> must have children named <RosType>");
180  ui->labelValidSyntax->setText(tr("Invalid: ") + errorStr);
181  return false;
182  }
183  if( type_el.hasAttribute("name") == false)
184  {
185  errorStr = tr("node <RosType> must have the attribute [name]");
186  ui->labelValidSyntax->setText(tr("Invalid: ") + errorStr);
187  return false;
188  }
189 
190  for ( auto rule_el = type_el.firstChildElement( ) ;
191  rule_el.isNull() == false;
192  rule_el = rule_el.nextSiblingElement( ) )
193  {
194  if( rule_el.nodeName() != "rule")
195  {
196  errorStr = tr("<RosType> must have children named <rule>");
197  ui->labelValidSyntax->setText(tr("Invalid: ") + errorStr);
198  return false;
199  }
200  if( !rule_el.hasAttribute("pattern") ||
201  !rule_el.hasAttribute("alias") ||
202  !rule_el.hasAttribute("substitution") )
203  {
204  errorStr = tr("<rule> must have the attributes 'pattern', 'alias' and 'substitution'");
205  ui->labelValidSyntax->setText(tr("Invalid: ") + errorStr);
206  return false;
207  }
208  }
209  }
210  ui->labelValidSyntax->setText(tr("Valid") + errorStr);
211  return true;
212 }
213 
215 {
216  QSettings settings;
217  settings.setValue("RuleEditing.text", ui->textEdit->toPlainText() );
218  this->close();
219 }
220 
221 void RuleEditing::closeEvent(QCloseEvent *event)
222 {
223  QSettings settings;
224  settings.setValue("RuleEditing.geometry", saveGeometry());
225  QWidget::closeEvent(event);
226 }
227 
229 {
230  bool valid = isValidXml();
231  ui->pushButtonSave->setEnabled(valid);
232 }
233 
235 {
236  this->close();
237 }
238 
240 {
241  QMessageBox::StandardButton reply;
242  reply = QMessageBox::question(0, tr("Warning"),
243  tr("Do you really want to overwrite these rules\n"),
244  QMessageBox::Yes | QMessageBox::No,
245  QMessageBox::No );
246  if( reply == QMessageBox::Yes )
247  {
248  ui->textEdit->setPlainText( DEFAULT_RULES );
249  }
250 }
251 
253 {
254  QSettings settings;
255  if( settings.contains("RuleEditing.text") )
256  {
257  return settings.value("RuleEditing.text").toString();
258  }
259  else{
260  return DEFAULT_RULES;
261  }
262 }
263 
265 {
266  using namespace RosIntrospection;
267  SubstitutionRuleMap rule_map;
268 
269  QDomDocument domDocument;
270 
271  if (!domDocument.setContent( getRenamingXML() , true))
272  {
273  return rule_map;
274  }
275  QDomElement root = domDocument.namedItem("SubstitutionRules").toElement();
276 
277  for ( auto type_el = root.firstChildElement("RosType") ;
278  type_el.isNull() == false;
279  type_el = type_el.nextSiblingElement("RosType") )
280  {
281  std::string type_name = type_el.attribute("name").toStdString();
282  std::vector<SubstitutionRule> rules_vect;
283 
284  for ( auto rule_el = type_el.firstChildElement("rule") ;
285  rule_el.isNull() == false;
286  rule_el = rule_el.nextSiblingElement("rule") )
287  {
288  std::string pattern = rule_el.attribute("pattern").toStdString();
289  std::string substitution = rule_el.attribute("substitution").toStdString();
290  std::string alias = rule_el.attribute("alias").toStdString();
291 
292  SubstitutionRule rule( pattern.c_str(),
293  alias.c_str(),
294  substitution.c_str() );
295 
296  rules_vect.push_back( rule );
297  }
298  rule_map.insert( std::make_pair( ROSType(type_name), std::move( rules_vect ) ));
299  }
300  return rule_map;
301 }
302 
const char * DEFAULT_RULES
Definition: rule_editing.cpp:9
QList< QRegExp > _xmlKeywordRegexes
Definition: rule_editing.h:39
virtual void highlightBlock(const QString &text)
XMLSyntaxHighlighter(QObject *parent)
QRegExp _xmlAttributeRegex
Definition: rule_editing.h:41
QTextCharFormat _xmlCommentFormat
Definition: rule_editing.h:37
void on_pushButtonReset_pressed()
void on_pushButtonSave_pressed()
void on_pushButtonCancel_pressed()
Ui::RuleEditing * ui
Definition: rule_editing.h:73
QTextCharFormat _xmlValueFormat
Definition: rule_editing.h:36
std::map< ROSType, std::vector< SubstitutionRule > > SubstitutionRuleMap
QTextCharFormat _xmlElementFormat
Definition: rule_editing.h:34
void highlightByRegex(const QTextCharFormat &format, const QRegExp &regex, const QString &text)
static RosIntrospection::SubstitutionRuleMap getRenamingRules()
QTextCharFormat _xmlKeywordFormat
Definition: rule_editing.h:33
virtual void closeEvent(QCloseEvent *event) override
XMLSyntaxHighlighter * _highlighter
Definition: rule_editing.h:75
QTimer _timer
Definition: rule_editing.h:76
bool isValidXml()
RuleEditing(QWidget *parent=0)
QTextCharFormat _xmlAttributeFormat
Definition: rule_editing.h:35
static QString getRenamingXML()


plotjuggler
Author(s): Davide Faconti
autogenerated on Sat Jul 6 2019 03:44:18