87 using tinyxml2::XMLElement;
89 tinyxml2::XMLDocument doc;
91 doc.Parse(urdf_string.c_str());
92 auto root = doc.RootElement();
95 std::string orig_urdf =
printXML(doc);
98 std::map<std::string, XMLElement*> transmission_elements;
99 for (XMLElement* element = root->FirstChildElement(
"transmission"); element !=
nullptr;
100 element = element->NextSiblingElement(element->Value()))
102 auto type_tag = element->FirstChildElement(
"type");
103 auto joint_tag = element->FirstChildElement(
"joint");
104 if (!type_tag || !type_tag->GetText() || !joint_tag || !joint_tag->Attribute(
"name"))
106 if (std::string(type_tag->GetText()) ==
"transmission_interface/SimpleTransmission")
107 transmission_elements[element->FirstChildElement(
"joint")->Attribute(
"name")] = element;
111 for (XMLElement* element = root->FirstChildElement(); element !=
nullptr; element = element->NextSiblingElement())
113 const std::string tag_name(element->Value());
114 if (tag_name ==
"link" && element->FirstChildElement(
"collision"))
116 XMLElement* inertial =
uniqueInsert(doc, *element,
"inertial");
117 uniqueInsert(doc, *inertial,
"mass", { {
"value",
"0.1" } });
118 uniqueInsert(doc, *inertial,
"origin", { {
"xyz",
"0 0 0" }, {
"rpy",
"0 0 0" } });
127 else if (tag_name ==
"joint")
129 const char* joint_type = element->Attribute(
"type");
130 const char* joint_name = element->Attribute(
"name");
131 if (!joint_type || !joint_name || strcmp(joint_type,
"fixed") == 0)
135 XMLElement* transmission;
136 auto it = transmission_elements.find(joint_name);
137 if (it != transmission_elements.end())
138 transmission = it->second;
141 transmission = doc.NewElement(
"transmission");
142 root->InsertEndChild(transmission);
143 transmission->SetAttribute(
"name", (std::string(
"trans_") + joint_name).c_str());
146 uniqueInsert(doc, *transmission,
"type", {},
"transmission_interface/SimpleTransmission");
149 auto* joint =
uniqueInsert(doc, *transmission,
"joint", { {
"name", joint_name } });
150 uniqueInsert(doc, *joint,
"hardwareInterface", {}, hw_interface.c_str());
152 auto actuator_name = joint_name + std::string(
"_motor");
153 auto* actuator =
uniqueInsert(doc, *transmission,
"actuator", { {
"name", actuator_name.c_str() } });
154 uniqueInsert(doc, *actuator,
"hardwareInterface", {}, hw_interface.c_str());
155 uniqueInsert(doc, *actuator,
"mechanicalReduction", {},
"1");
160 XMLElement* gazebo =
uniqueInsert(doc, *root,
"gazebo");
161 XMLElement* plugin =
uniqueInsert(doc, *gazebo,
"plugin", { {
"name",
"gazebo_ros_control",
true } });
165 std::string new_urdf =
printXML(doc);
167 return orig_urdf == new_urdf ? std::string() : new_urdf;
190 tinyxml2::XMLDocument doc;
191 doc.Parse(new_urdf_contents.c_str());
194 error_row = doc.ErrorLineNum();
195 error_description = doc.ErrorStr();
tinyxml2::XMLElement * uniqueInsert(tinyxml2::XMLDocument &doc, tinyxml2::XMLElement &element, const char *tag, const std::vector< XMLAttribute > &attributes={}, const char *text=nullptr)
Insert a new XML element with a given tag, attributes, and text.