Skip to content

Commit

Permalink
Switch from TinyXML to TinyXML2
Browse files Browse the repository at this point in the history
The library TinyXML is considered to be unmaintained and
since all future development is focused on TinyXML2 this
patch updates srdfdom to use TinyXML2.

Signed-off-by: Dmitry Rozhkov <dmitry.rozhkov@linux.intel.com>
  • Loading branch information
Dmitry Rozhkov authored and rhaschke committed Aug 19, 2020
1 parent 647ebfb commit f96609f
Show file tree
Hide file tree
Showing 6 changed files with 185 additions and 173 deletions.
8 changes: 4 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,12 @@ find_package(urdfdom_headers REQUIRED)

find_package(catkin REQUIRED COMPONENTS cmake_modules urdf)

find_package(TinyXML REQUIRED)
find_package(TinyXML2 REQUIRED)

include_directories(
include
${Boost_INCLUDE_DIR}
${TinyXML_INCLUDE_DIRS}
${TinyXML2_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
${console_bridge_INCLUDE_DIRS}
${urdfdom_headers_INCLUDE_DIRS}
Expand All @@ -26,15 +26,15 @@ catkin_python_setup()
catkin_package(
LIBRARIES ${PROJECT_NAME}
INCLUDE_DIRS include
DEPENDS TinyXML console_bridge urdfdom_headers
DEPENDS TinyXML2 console_bridge urdfdom_headers
)

add_library(${PROJECT_NAME}
src/model.cpp
src/srdf_writer.cpp
)
set_target_properties(${PROJECT_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION})
target_link_libraries(${PROJECT_NAME} ${TinyXML_LIBRARIES} ${catkin_LIBRARIES} ${console_bridge_LIBRARIES} ${urdfdom_headers_LIBRARIES})
target_link_libraries(${PROJECT_NAME} ${TinyXML2_LIBRARIES} ${catkin_LIBRARIES} ${console_bridge_LIBRARIES} ${urdfdom_headers_LIBRARIES})


install(TARGETS ${PROJECT_NAME}
Expand Down
26 changes: 13 additions & 13 deletions include/srdfdom/model.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,9 +41,9 @@
#include <string>
#include <vector>
#include <utility>
#include <urdf/model.h> // TODO: replace with urdf_model/types.h in Lunar
#include <urdf/model.h>
#include <memory>
#include <tinyxml.h>
#include <tinyxml2.h>

/// Main namespace
namespace srdf
Expand All @@ -60,10 +60,10 @@ class Model
{
}

/// \brief Load Model from TiXMLElement
bool initXml(const urdf::ModelInterface& urdf_model, TiXmlElement* xml);
/// \brief Load Model from TiXMLDocument
bool initXml(const urdf::ModelInterface& urdf_model, TiXmlDocument* xml);
/// \brief Load Model from XMLElement
bool initXml(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* xml);
/// \brief Load Model from XMLDocument
bool initXml(const urdf::ModelInterface& urdf_model, tinyxml2::XMLDocument* xml);
/// \brief Load Model given a filename
bool initFile(const urdf::ModelInterface& urdf_model, const std::string& filename);
/// \brief Load Model from a XML-string
Expand Down Expand Up @@ -251,13 +251,13 @@ class Model
void clear();

private:
void loadVirtualJoints(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
void loadGroups(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
void loadGroupStates(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
void loadEndEffectors(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
void loadLinkSphereApproximations(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
void loadDisabledCollisions(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
void loadPassiveJoints(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml);
void loadVirtualJoints(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
void loadGroups(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
void loadGroupStates(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
void loadEndEffectors(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
void loadLinkSphereApproximations(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
void loadDisabledCollisions(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);
void loadPassiveJoints(const urdf::ModelInterface& urdf_model, tinyxml2::XMLElement* robot_xml);

std::string name_;
std::vector<Group> groups_;
Expand Down
16 changes: 8 additions & 8 deletions include/srdfdom/srdf_writer.h
Original file line number Diff line number Diff line change
Expand Up @@ -109,56 +109,56 @@ class SRDFWriter
*
* @return TinyXML document that contains current SRDF data in this class
*/
TiXmlDocument generateSRDF();
void generateSRDF(tinyxml2::XMLDocument& document);

/**
* Generate XML for SRDF groups
*
* @param root - TinyXML root element to attach sub elements to
*/
void createGroupsXML(TiXmlElement* root);
void createGroupsXML(tinyxml2::XMLElement* root);

/**
* Generate XML for SRDF link collision spheres
*
* @param root - TinyXML root element to attach sub elements to
*/
void createLinkSphereApproximationsXML(TiXmlElement* root);
void createLinkSphereApproximationsXML(tinyxml2::XMLElement* root);

/**
* Generate XML for SRDF disabled collisions of robot link pairs
*
* @param root - TinyXML root element to attach sub elements to
*/
void createDisabledCollisionsXML(TiXmlElement* root);
void createDisabledCollisionsXML(tinyxml2::XMLElement* root);

/**
* Generate XML for SRDF group states of each joint's position
*
* @param root - TinyXML root element to attach sub elements to
*/
void createGroupStatesXML(TiXmlElement* root);
void createGroupStatesXML(tinyxml2::XMLElement* root);

/**
* Generate XML for SRDF end effectors
*
* @param root - TinyXML root element to attach sub elements to
*/
void createEndEffectorsXML(TiXmlElement* root);
void createEndEffectorsXML(tinyxml2::XMLElement* root);

/**
* Generate XML for SRDF virtual joints
*
* @param root - TinyXML root element to attach sub elements to
*/
void createVirtualJointsXML(TiXmlElement* root);
void createVirtualJointsXML(tinyxml2::XMLElement* root);

/**
* Generate XML for SRDF passive joints
*
* @param root - TinyXML root element to attach sub elements to
*/
void createPassiveJointsXML(TiXmlElement* root);
void createPassiveJointsXML(tinyxml2::XMLElement* root);

// ******************************************************************************************
// Group Datastructures
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

<depend>boost</depend>
<depend>urdf</depend>
<depend>tinyxml</depend>
<depend>tinyxml2</depend>

<build_depend>cmake_modules</build_depend>
<build_depend>libconsole-bridge-dev</build_depend>
Expand Down
60 changes: 33 additions & 27 deletions src/model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,11 @@
#include <set>
#include <limits>

void srdf::Model::loadVirtualJoints(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml)
using namespace tinyxml2;

void srdf::Model::loadVirtualJoints(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
{
for (TiXmlElement* vj_xml = robot_xml->FirstChildElement("virtual_joint"); vj_xml;
for (XMLElement* vj_xml = robot_xml->FirstChildElement("virtual_joint"); vj_xml;
vj_xml = vj_xml->NextSiblingElement("virtual_joint"))
{
const char* jname = vj_xml->Attribute("name");
Expand Down Expand Up @@ -98,9 +100,9 @@ void srdf::Model::loadVirtualJoints(const urdf::ModelInterface& urdf_model, TiXm
}
}

void srdf::Model::loadGroups(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml)
void srdf::Model::loadGroups(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
{
for (TiXmlElement* group_xml = robot_xml->FirstChildElement("group"); group_xml;
for (XMLElement* group_xml = robot_xml->FirstChildElement("group"); group_xml;
group_xml = group_xml->NextSiblingElement("group"))
{
const char* gname = group_xml->Attribute("name");
Expand All @@ -114,7 +116,7 @@ void srdf::Model::loadGroups(const urdf::ModelInterface& urdf_model, TiXmlElemen
boost::trim(g.name_);

// get the links in the groups
for (TiXmlElement* link_xml = group_xml->FirstChildElement("link"); link_xml;
for (XMLElement* link_xml = group_xml->FirstChildElement("link"); link_xml;
link_xml = link_xml->NextSiblingElement("link"))
{
const char* lname = link_xml->Attribute("name");
Expand All @@ -133,7 +135,7 @@ void srdf::Model::loadGroups(const urdf::ModelInterface& urdf_model, TiXmlElemen
}

// get the joints in the groups
for (TiXmlElement* joint_xml = group_xml->FirstChildElement("joint"); joint_xml;
for (XMLElement* joint_xml = group_xml->FirstChildElement("joint"); joint_xml;
joint_xml = joint_xml->NextSiblingElement("joint"))
{
const char* jname = joint_xml->Attribute("name");
Expand Down Expand Up @@ -162,7 +164,7 @@ void srdf::Model::loadGroups(const urdf::ModelInterface& urdf_model, TiXmlElemen
}

// get the chains in the groups
for (TiXmlElement* chain_xml = group_xml->FirstChildElement("chain"); chain_xml;
for (XMLElement* chain_xml = group_xml->FirstChildElement("chain"); chain_xml;
chain_xml = chain_xml->NextSiblingElement("chain"))
{
const char* base = chain_xml->Attribute("base_link");
Expand Down Expand Up @@ -221,7 +223,7 @@ void srdf::Model::loadGroups(const urdf::ModelInterface& urdf_model, TiXmlElemen
}

// get the subgroups in the groups
for (TiXmlElement* subg_xml = group_xml->FirstChildElement("group"); subg_xml;
for (XMLElement* subg_xml = group_xml->FirstChildElement("group"); subg_xml;
subg_xml = subg_xml->NextSiblingElement("group"))
{
const char* sub = subg_xml->Attribute("name");
Expand Down Expand Up @@ -280,9 +282,9 @@ void srdf::Model::loadGroups(const urdf::ModelInterface& urdf_model, TiXmlElemen
}
}

void srdf::Model::loadGroupStates(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml)
void srdf::Model::loadGroupStates(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
{
for (TiXmlElement* gstate_xml = robot_xml->FirstChildElement("group_state"); gstate_xml;
for (XMLElement* gstate_xml = robot_xml->FirstChildElement("group_state"); gstate_xml;
gstate_xml = gstate_xml->NextSiblingElement("group_state"))
{
const char* sname = gstate_xml->Attribute("name");
Expand Down Expand Up @@ -316,7 +318,7 @@ void srdf::Model::loadGroupStates(const urdf::ModelInterface& urdf_model, TiXmlE
}

// get the joint values in the group state
for (TiXmlElement* joint_xml = gstate_xml->FirstChildElement("joint"); joint_xml;
for (XMLElement* joint_xml = gstate_xml->FirstChildElement("joint"); joint_xml;
joint_xml = joint_xml->NextSiblingElement("joint"))
{
const char* jname = joint_xml->Attribute("name");
Expand Down Expand Up @@ -376,9 +378,9 @@ void srdf::Model::loadGroupStates(const urdf::ModelInterface& urdf_model, TiXmlE
}
}

void srdf::Model::loadEndEffectors(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml)
void srdf::Model::loadEndEffectors(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
{
for (TiXmlElement* eef_xml = robot_xml->FirstChildElement("end_effector"); eef_xml;
for (XMLElement* eef_xml = robot_xml->FirstChildElement("end_effector"); eef_xml;
eef_xml = eef_xml->NextSiblingElement("end_effector"))
{
const char* ename = eef_xml->Attribute("name");
Expand Down Expand Up @@ -434,9 +436,9 @@ void srdf::Model::loadEndEffectors(const urdf::ModelInterface& urdf_model, TiXml
}
}

void srdf::Model::loadLinkSphereApproximations(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml)
void srdf::Model::loadLinkSphereApproximations(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
{
for (TiXmlElement* cslink_xml = robot_xml->FirstChildElement("link_sphere_approximation"); cslink_xml;
for (XMLElement* cslink_xml = robot_xml->FirstChildElement("link_sphere_approximation"); cslink_xml;
cslink_xml = cslink_xml->NextSiblingElement("link_sphere_approximation"))
{
int non_0_radius_sphere_cnt = 0;
Expand All @@ -457,7 +459,7 @@ void srdf::Model::loadLinkSphereApproximations(const urdf::ModelInterface& urdf_

// get the spheres for this link
int cnt = 0;
for (TiXmlElement* sphere_xml = cslink_xml->FirstChildElement("sphere"); sphere_xml;
for (XMLElement* sphere_xml = cslink_xml->FirstChildElement("sphere"); sphere_xml;
sphere_xml = sphere_xml->NextSiblingElement("sphere"), cnt++)
{
const char* s_center = sphere_xml->Attribute("center");
Expand Down Expand Up @@ -531,9 +533,9 @@ void srdf::Model::loadLinkSphereApproximations(const urdf::ModelInterface& urdf_
}
}

void srdf::Model::loadDisabledCollisions(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml)
void srdf::Model::loadDisabledCollisions(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
{
for (TiXmlElement* c_xml = robot_xml->FirstChildElement("disable_collisions"); c_xml;
for (XMLElement* c_xml = robot_xml->FirstChildElement("disable_collisions"); c_xml;
c_xml = c_xml->NextSiblingElement("disable_collisions"))
{
const char* link1 = c_xml->Attribute("link1");
Expand Down Expand Up @@ -563,10 +565,14 @@ void srdf::Model::loadDisabledCollisions(const urdf::ModelInterface& urdf_model,
}
}

void srdf::Model::loadPassiveJoints(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml)
void srdf::Model::loadPassiveJoints(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
{
for (TiXmlElement* c_xml = robot_xml->FirstChildElement("passive_joint"); c_xml;
c_xml = c_xml->NextSiblingElement("passive_joint"))
for (XMLElement* c_xml = robot_xml->FirstChildElement("passive_joint"); c_xml; c_xml = c_xml->NextSiblingElement("pas"
"siv"
"e_"
"joi"
"n"
"t"))
{
const char* name = c_xml->Attribute("name");
if (!name)
Expand All @@ -592,10 +598,10 @@ void srdf::Model::loadPassiveJoints(const urdf::ModelInterface& urdf_model, TiXm
}
}

bool srdf::Model::initXml(const urdf::ModelInterface& urdf_model, TiXmlElement* robot_xml)
bool srdf::Model::initXml(const urdf::ModelInterface& urdf_model, XMLElement* robot_xml)
{
clear();
if (!robot_xml || robot_xml->ValueStr() != "robot")
if (!robot_xml || strcmp(robot_xml->Value(), "robot") != 0)
{
CONSOLE_BRIDGE_logError("Could not find the 'robot' element in the xml file");
return false;
Expand Down Expand Up @@ -624,9 +630,9 @@ bool srdf::Model::initXml(const urdf::ModelInterface& urdf_model, TiXmlElement*
return true;
}

bool srdf::Model::initXml(const urdf::ModelInterface& urdf_model, TiXmlDocument* xml)
bool srdf::Model::initXml(const urdf::ModelInterface& urdf_model, XMLDocument* xml)
{
TiXmlElement* robot_xml = xml ? xml->FirstChildElement("robot") : NULL;
XMLElement* robot_xml = xml ? xml->FirstChildElement("robot") : NULL;
if (!robot_xml)
{
CONSOLE_BRIDGE_logError("Could not find the 'robot' element in the xml file");
Expand Down Expand Up @@ -660,11 +666,11 @@ bool srdf::Model::initFile(const urdf::ModelInterface& urdf_model, const std::st

bool srdf::Model::initString(const urdf::ModelInterface& urdf_model, const std::string& xmlstring)
{
TiXmlDocument xml_doc;
XMLDocument xml_doc;
xml_doc.Parse(xmlstring.c_str());
if (xml_doc.Error())
{
CONSOLE_BRIDGE_logError("Could not parse the SRDF XML File. %s", xml_doc.ErrorDesc());
CONSOLE_BRIDGE_logError("Could not parse the SRDF XML File. %s", xml_doc.ErrorStr());
return false;
}
return initXml(urdf_model, &xml_doc);
Expand Down
Loading

0 comments on commit f96609f

Please sign in to comment.