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


plotjuggler_ros
Author(s): Davide Faconti
autogenerated on Fri Jun 23 2023 02:28:03