2 #include "ui_rule_editing.h" 3 #include <QDomDocument> 5 #include <QPlainTextEdit> 10 "<SubstitutionRules>\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" 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" 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" 30 "<RosType name=\"pal_statistics_msgs/Statistics\">\n" 31 " <rule pattern=\"statistics.#/value\" alias=\"statistics.#/name\" substitution=\"@\" />\n" 33 "</SubstitutionRules>\n" 37 QSyntaxHighlighter(parent)
44 QSyntaxHighlighter(parent)
51 QSyntaxHighlighter(parent)
61 while(xmlElementIndex >= 0)
67 xmlElementIndex =
_xmlElementRegex.indexIn(text, matchedPos + matchedLength);
71 typedef QList<QRegExp>::const_iterator Iter;
74 const QRegExp & regex = *it;
84 const QRegExp & regex,
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(
"<") << QRegExp(
"</")
129 restoreGeometry(settings.value(
"RuleEditing.geometry").toByteArray());
134 _timer.setSingleShot(
false);
137 const QFont fixedFont = QFontDatabase::systemFont(QFontDatabase::FixedFont);
139 ui->textEdit->setFont(fixedFont);
153 int errorLine, errorColumn;
156 QDomDocument domDocument;
157 QString text =
ui->textEdit->toPlainText();
159 if (!domDocument.setContent(text ,
true,
160 &errorStr, &errorLine, &errorColumn))
162 ui->labelValidSyntax->setText(
"Invalid XML: " + errorStr);
165 QDomElement root = domDocument.namedItem(
"SubstitutionRules").toElement();
168 errorStr = tr(
"the root node should be <SubstitutionRules>");
169 ui->labelValidSyntax->setText(tr(
"Invalid: ") + errorStr);
173 for (
auto type_el = root.firstChildElement( ) ;
174 type_el.isNull() ==
false;
175 type_el = type_el.nextSiblingElement() )
177 if( type_el.nodeName() !=
"RosType")
179 errorStr = tr(
"<SubstitutionRules> must have children named <RosType>");
180 ui->labelValidSyntax->setText(tr(
"Invalid: ") + errorStr);
183 if( type_el.hasAttribute(
"name") ==
false)
185 errorStr = tr(
"node <RosType> must have the attribute [name]");
186 ui->labelValidSyntax->setText(tr(
"Invalid: ") + errorStr);
190 for (
auto rule_el = type_el.firstChildElement( ) ;
191 rule_el.isNull() ==
false;
192 rule_el = rule_el.nextSiblingElement( ) )
194 if( rule_el.nodeName() !=
"rule")
196 errorStr = tr(
"<RosType> must have children named <rule>");
197 ui->labelValidSyntax->setText(tr(
"Invalid: ") + errorStr);
200 if( !rule_el.hasAttribute(
"pattern") ||
201 !rule_el.hasAttribute(
"alias") ||
202 !rule_el.hasAttribute(
"substitution") )
204 errorStr = tr(
"<rule> must have the attributes 'pattern', 'alias' and 'substitution'");
205 ui->labelValidSyntax->setText(tr(
"Invalid: ") + errorStr);
210 ui->labelValidSyntax->setText(tr(
"Valid") + errorStr);
217 settings.setValue(
"RuleEditing.text",
ui->textEdit->toPlainText() );
224 settings.setValue(
"RuleEditing.geometry", saveGeometry());
225 QWidget::closeEvent(event);
231 ui->pushButtonSave->setEnabled(valid);
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,
246 if( reply == QMessageBox::Yes )
255 if( settings.contains(
"RuleEditing.text") )
257 return settings.value(
"RuleEditing.text").toString();
269 QDomDocument domDocument;
275 QDomElement root = domDocument.namedItem(
"SubstitutionRules").toElement();
277 for (
auto type_el = root.firstChildElement(
"RosType") ;
278 type_el.isNull() ==
false;
279 type_el = type_el.nextSiblingElement(
"RosType") )
281 std::string type_name = type_el.attribute(
"name").toStdString();
282 std::vector<SubstitutionRule> rules_vect;
284 for (
auto rule_el = type_el.firstChildElement(
"rule") ;
285 rule_el.isNull() ==
false;
286 rule_el = rule_el.nextSiblingElement(
"rule") )
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();
294 substitution.c_str() );
296 rules_vect.push_back( rule );
298 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()
QTextCharFormat _xmlKeywordFormat
virtual void closeEvent(QCloseEvent *event) override
XMLSyntaxHighlighter * _highlighter
RuleEditing(QWidget *parent=0)
QTextCharFormat _xmlAttributeFormat
static QString getRenamingXML()