2 #include "ui_rule_editing.h" 3 #include <QDomDocument> 5 #include <QPlainTextEdit> 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" 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" 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" 35 "<RosType name=\"pal_statistics_msgs/Statistics\">\n" 36 " <rule pattern=\"statistics.#/value\" alias=\"statistics.#/name\" substitution=\"@\" />\n" 38 "</SubstitutionRules>\n";
62 while (xmlElementIndex >= 0)
68 xmlElementIndex =
_xmlElementRegex.indexIn(text, matchedPos + matchedLength);
76 const QRegExp& regex = *
it;
87 int index = regex.indexIn(text);
90 int matchedLength = regex.matchedLength();
91 setFormat(index, matchedLength, format);
92 index = regex.indexIn(text, index + matchedLength);
104 << QRegExp(
"</") << QRegExp(
"\\?>");
126 restoreGeometry(settings.value(
"RuleEditing.geometry").toByteArray());
131 _timer.setSingleShot(
false);
134 const QFont fixedFont = QFontDatabase::systemFont(QFontDatabase::FixedFont);
136 ui->textEdit->setFont(fixedFont);
149 int errorLine, errorColumn;
152 QDomDocument domDocument;
153 QString
text =
ui->textEdit->toPlainText();
155 if (!domDocument.setContent(text,
true, &errorStr, &errorLine, &errorColumn))
157 ui->labelValidSyntax->setText(
"Invalid XML: " + errorStr);
160 QDomElement root = domDocument.namedItem(
"SubstitutionRules").toElement();
164 errorStr = tr(
"the root node should be <SubstitutionRules>");
165 ui->labelValidSyntax->setText(tr(
"Invalid: ") + errorStr);
169 for (
auto type_el = root.firstChildElement(); type_el.isNull() ==
false; type_el = type_el.nextSiblingElement())
171 if (type_el.nodeName() !=
"RosType")
173 errorStr = tr(
"<SubstitutionRules> must have children named <RosType>");
174 ui->labelValidSyntax->setText(tr(
"Invalid: ") + errorStr);
177 if (type_el.hasAttribute(
"name") ==
false)
179 errorStr = tr(
"node <RosType> must have the attribute [name]");
180 ui->labelValidSyntax->setText(tr(
"Invalid: ") + errorStr);
184 for (
auto rule_el = type_el.firstChildElement(); rule_el.isNull() ==
false; rule_el = rule_el.nextSiblingElement())
186 if (rule_el.nodeName() !=
"rule")
188 errorStr = tr(
"<RosType> must have children named <rule>");
189 ui->labelValidSyntax->setText(tr(
"Invalid: ") + errorStr);
192 if (!rule_el.hasAttribute(
"pattern") || !rule_el.hasAttribute(
"alias") || !rule_el.hasAttribute(
"substitution"))
194 errorStr = tr(
"<rule> must have the attributes 'pattern', 'alias' and 'substitution'");
195 ui->labelValidSyntax->setText(tr(
"Invalid: ") + errorStr);
200 ui->labelValidSyntax->setText(tr(
"Valid") + errorStr);
207 settings.setValue(
"RuleEditing.text",
ui->textEdit->toPlainText());
214 settings.setValue(
"RuleEditing.geometry", saveGeometry());
215 QWidget::closeEvent(event);
221 ui->pushButtonSave->setEnabled(valid);
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)
243 if (settings.contains(
"RuleEditing.text"))
245 return settings.value(
"RuleEditing.text").toString();
258 QDomDocument domDocument;
264 QDomElement root = domDocument.namedItem(
"SubstitutionRules").toElement();
266 for (
auto type_el = root.firstChildElement(
"RosType"); type_el.isNull() ==
false;
267 type_el = type_el.nextSiblingElement(
"RosType"))
269 std::string
type_name = type_el.attribute(
"name").toStdString();
270 std::vector<SubstitutionRule> rules_vect;
272 for (
auto rule_el = type_el.firstChildElement(
"rule"); rule_el.isNull() ==
false;
273 rule_el = rule_el.nextSiblingElement(
"rule"))
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();
279 SubstitutionRule rule(pattern.c_str(), alias.c_str(), substitution.c_str());
281 rules_vect.push_back(rule);
283 rule_map.insert(std::make_pair(
ROSType(type_name), std::move(rules_vect)));
const char * DEFAULT_RULES
QList< QRegExp > _xmlKeywordRegexes
virtual void highlightBlock(const QString &text)
XMLSyntaxHighlighter(QObject *parent)
QRegExp _xmlAttributeRegex
QTextCharFormat _xmlCommentFormat
void on_pushButtonReset_pressed()
void on_pushButtonSave_pressed()
void on_pushButtonCancel_pressed()
QTextCharFormat _xmlValueFormat
std::map< ROSType, std::vector< SubstitutionRule > > SubstitutionRuleMap
QTextCharFormat _xmlElementFormat
void highlightByRegex(const QTextCharFormat &format, const QRegExp ®ex, const QString &text)
static RosIntrospection::SubstitutionRuleMap getRenamingRules()
std::string type_name(lua_State *L, type t)
FMT_INLINE std::basic_string< Char > format(const S &format_str, Args &&... args)
QTextCharFormat _xmlKeywordFormat
virtual void closeEvent(QCloseEvent *event) override
XMLSyntaxHighlighter * _highlighter
RuleEditing(QWidget *parent=0)
QTextCharFormat _xmlAttributeFormat
static QString getRenamingXML()