moveit2
The MoveIt Motion Planning Framework for ROS 2.
simulation.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, PickNik Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PickNik Robotics nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: David V. Lu!! */
36 
38 
39 namespace moveit_setup
40 {
41 namespace simulation
42 {
44 {
45  urdf_config_ = config_data_->get<URDFConfig>("urdf");
46 }
47 
48 // ******************************************************************************************
49 // Helper function to get the controller that is controlling the joint
50 // ******************************************************************************************
51 std::string Simulation::getJointHardwareInterface(const std::string& joint_name)
52 {
71  // If the joint was not found in any controller return EffortJointInterface
72  return "hardware_interface/EffortJointInterface";
73 }
74 
75 std::string printXML(const tinyxml2::XMLDocument& doc)
76 {
77  tinyxml2::XMLPrinter printer;
78  doc.Accept(&printer);
79  return printer.CStr();
80 }
81 
82 // ******************************************************************************************
83 // Writes a Gazebo compatible robot URDF to gazebo_compatible_urdf_string_
84 // ******************************************************************************************
86 {
87  using tinyxml2::XMLElement;
88 
89  tinyxml2::XMLDocument doc;
90  std::string urdf_string = urdf_config_->getURDFContents();
91  doc.Parse(urdf_string.c_str());
92  auto root = doc.RootElement();
93 
94  // Normalize original urdf_string_
95  std::string orig_urdf = printXML(doc);
96 
97  // Map existing SimpleTransmission elements to their joint name
98  std::map<std::string, XMLElement*> transmission_elements;
99  for (XMLElement* element = root->FirstChildElement("transmission"); element != nullptr;
100  element = element->NextSiblingElement(element->Value()))
101  {
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"))
105  continue; // ignore invalid tags
106  if (std::string(type_tag->GetText()) == "transmission_interface/SimpleTransmission")
107  transmission_elements[element->FirstChildElement("joint")->Attribute("name")] = element;
108  }
109 
110  // Loop through Link and Joint elements and add Gazebo tags if not present
111  for (XMLElement* element = root->FirstChildElement(); element != nullptr; element = element->NextSiblingElement())
112  {
113  const std::string tag_name(element->Value());
114  if (tag_name == "link" && element->FirstChildElement("collision"))
115  {
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" } });
119  uniqueInsert(doc, *inertial, "inertia",
120  { { "ixx", "0.03" },
121  { "iyy", "0.03" },
122  { "izz", "0.03" },
123  { "ixy", "0.0" },
124  { "ixz", "0.0" },
125  { "iyz", "0.0" } });
126  }
127  else if (tag_name == "joint")
128  {
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)
132  continue; // skip invalid or fixed joints
133 
134  // find existing or create new transmission element for this joint
135  XMLElement* transmission;
136  auto it = transmission_elements.find(joint_name);
137  if (it != transmission_elements.end())
138  transmission = it->second;
139  else
140  {
141  transmission = doc.NewElement("transmission");
142  root->InsertEndChild(transmission);
143  transmission->SetAttribute("name", (std::string("trans_") + joint_name).c_str());
144  }
145 
146  uniqueInsert(doc, *transmission, "type", {}, "transmission_interface/SimpleTransmission");
147 
148  std::string hw_interface = getJointHardwareInterface(joint_name);
149  auto* joint = uniqueInsert(doc, *transmission, "joint", { { "name", joint_name } });
150  uniqueInsert(doc, *joint, "hardwareInterface", {}, hw_interface.c_str());
151 
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");
156  }
157  }
158 
159  // Add gazebo_ros_control plugin which reads the transmission tags
160  XMLElement* gazebo = uniqueInsert(doc, *root, "gazebo");
161  XMLElement* plugin = uniqueInsert(doc, *gazebo, "plugin", { { "name", "gazebo_ros_control", true } });
162  uniqueInsert(doc, *plugin, "robotNamespace", {}, "/");
163 
164  // generate new URDF
165  std::string new_urdf = printXML(doc);
166  // and return it when there are changes
167  return orig_urdf == new_urdf ? std::string() : new_urdf;
168 }
169 
170 // ******************************************************************************************
171 // Output Gazebo URDF file
172 // ******************************************************************************************
173 bool Simulation::outputGazeboURDFFile(const std::filesystem::path& file_path)
174 {
175  std::ofstream os(file_path, std::ios_base::trunc);
176  if (!os.good())
177  {
178  RCLCPP_ERROR_STREAM(*logger_, "Unable to open file for writing " << file_path);
179  return false;
180  }
181 
182  os << gazebo_urdf_string_.c_str() << std::endl;
183  os.close();
184 
185  return true;
186 }
187 
188 bool Simulation::isValidXML(const std::string& new_urdf_contents, int& error_row, std::string& error_description) const
189 {
190  tinyxml2::XMLDocument doc;
191  doc.Parse(new_urdf_contents.c_str());
192  if (doc.Error())
193  {
194  error_row = doc.ErrorLineNum();
195  error_description = doc.ErrorStr();
196  }
197  return !doc.Error();
198 }
199 
200 } // namespace simulation
201 } // namespace moveit_setup
DataWarehousePtr config_data_
Definition: setup_step.hpp:97
std::shared_ptr< rclcpp::Logger > logger_
Definition: setup_step.hpp:99
std::string gazebo_urdf_string_
Gazebo URDF robot model string.
Definition: simulation.hpp:104
void onInit() override
Overridable initialization method.
Definition: simulation.cpp:43
std::shared_ptr< URDFConfig > urdf_config_
Definition: simulation.hpp:100
bool isValidXML(const std::string &new_urdf_contents, int &error_row, std::string &error_description) const
Check if the given xml is valid.
Definition: simulation.cpp:188
bool outputGazeboURDFFile(const std::filesystem::path &file_path)
Definition: simulation.cpp:173
std::string getGazeboCompatibleURDF()
Parses the existing urdf and constructs a string from it with the elements required by gazebo simulat...
Definition: simulation.cpp:85
std::string getJointHardwareInterface(const std::string &joint_name)
Helper function to get the controller that is controlling the joint.
Definition: simulation.cpp:51
std::string printXML(const tinyxml2::XMLDocument &doc)
Definition: simulation.cpp:75
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.
Definition: utilities.cpp:100