Skip to content
This repository has been archived by the owner on Nov 6, 2020. It is now read-only.

Commit

Permalink
Switch from tinyxml -> tinyxml2
Browse files Browse the repository at this point in the history
  • Loading branch information
rotu committed Apr 27, 2020
1 parent b77e51c commit d88bc41
Show file tree
Hide file tree
Showing 17 changed files with 209 additions and 220 deletions.
2 changes: 1 addition & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ compiler:
script: "./.travis/build"
before_install:
- sudo apt-get update -qq
- sudo apt-get install -qq libtinyxml-dev
- sudo apt-get install -qq libtinyxml2-dev
matrix:
allow_failures:
- compiler: clang
6 changes: 3 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,9 @@ endif (MSVC OR MSVC90 OR MSVC10)

set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake")

find_package(tinyxml_vendor REQUIRED)
find_package(TinyXML REQUIRED)
include_directories(SYSTEM ${TinyXML_INCLUDE_DIRS})
find_package(tinyxml2_vendor REQUIRED)
find_package(TinyXML2 REQUIRED)
include_directories(SYSTEM ${TinyXML2_INCLUDE_DIRS})

find_package(urdfdom_headers 1.0 REQUIRED)
include_directories(SYSTEM ${urdfdom_headers_INCLUDE_DIRS})
Expand Down
74 changes: 0 additions & 74 deletions cmake/FindTinyXML.cmake

This file was deleted.

2 changes: 1 addition & 1 deletion cmake/urdfdom-config.cmake.in
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ if (@PKG_NAME@_CONFIG_INCLUDED)
endif()
set(@PKG_NAME@_CONFIG_INCLUDED TRUE)

set(@PKG_NAME@_INCLUDE_DIRS "@CMAKE_INSTALL_PREFIX@/include" "@TinyXML_INCLUDE_DIRS@")
set(@PKG_NAME@_INCLUDE_DIRS "@CMAKE_INSTALL_PREFIX@/include" "@TinyXML2_INCLUDE_DIRS@")

foreach(lib @PKG_LIBRARIES@)
set(onelib "${lib}-NOTFOUND")
Expand Down
8 changes: 4 additions & 4 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,16 +13,16 @@

<build_depend>console_bridge_vendor</build_depend>
<build_depend>libconsole-bridge-dev</build_depend>
<build_depend>tinyxml</build_depend>
<build_depend>tinyxml_vendor</build_depend>
<build_depend>tinyxml2</build_depend>
<build_depend>tinyxml2_vendor</build_depend>
<build_depend version_gte="0.2.3">urdfdom_headers</build_depend>

<buildtool_depend>cmake</buildtool_depend>

<exec_depend>console_bridge_vendor</exec_depend>
<exec_depend>libconsole-bridge-dev</exec_depend>
<exec_depend>tinyxml</exec_depend>
<exec_depend>tinyxml_vendor</exec_depend>
<exec_depend>tinyxml2</exec_depend>
<exec_depend>tinyxml2_vendor</exec_depend>
<exec_depend version_gte="0.2.3">urdfdom_headers</exec_depend>

<export>
Expand Down
16 changes: 8 additions & 8 deletions urdf_parser/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,19 +1,19 @@
include_directories(include)

add_library(urdfdom_world SHARED src/pose.cpp src/model.cpp src/link.cpp src/joint.cpp src/world.cpp)
target_link_libraries(urdfdom_world ${TinyXML_LIBRARIES} ${console_bridge_LIBRARIES})
add_library(urdfdom_world SHARED src/pose.cpp src/model.cpp src/link.cpp src/joint.cpp src/world.cpp src/xml_helpers.cpp)
target_link_libraries(urdfdom_world ${TinyXML2_LIBRARIES} ${console_bridge_LIBRARIES})
set_target_properties(urdfdom_world PROPERTIES SOVERSION ${URDF_MAJOR_MINOR_VERSION})

add_library(urdfdom_model SHARED src/pose.cpp src/model.cpp src/link.cpp src/joint.cpp)
target_link_libraries(urdfdom_model ${TinyXML_LIBRARIES} ${console_bridge_LIBRARIES})
add_library(urdfdom_model SHARED src/pose.cpp src/model.cpp src/link.cpp src/joint.cpp src/xml_helpers.cpp)
target_link_libraries(urdfdom_model ${TinyXML2_LIBRARIES} ${console_bridge_LIBRARIES})
set_target_properties(urdfdom_model PROPERTIES SOVERSION ${URDF_MAJOR_MINOR_VERSION})

add_library(urdfdom_sensor SHARED src/urdf_sensor.cpp)
target_link_libraries(urdfdom_sensor urdfdom_model ${TinyXML_LIBRARIES} ${console_bridge_LIBRARIES})
add_library(urdfdom_sensor SHARED src/urdf_sensor.cpp src/xml_helpers.cpp)
target_link_libraries(urdfdom_sensor urdfdom_model ${TinyXML2_LIBRARIES} ${console_bridge_LIBRARIES})
set_target_properties(urdfdom_sensor PROPERTIES SOVERSION ${URDF_MAJOR_MINOR_VERSION})

add_library(urdfdom_model_state SHARED src/urdf_model_state.cpp src/twist.cpp)
target_link_libraries(urdfdom_model_state ${TinyXML_LIBRARIES} ${console_bridge_LIBRARIES})
add_library(urdfdom_model_state SHARED src/urdf_model_state.cpp src/twist.cpp src/xml_helpers.cpp)
target_link_libraries(urdfdom_model_state ${TinyXML2_LIBRARIES} ${console_bridge_LIBRARIES})
set_target_properties(urdfdom_model_state PROPERTIES SOVERSION ${URDF_MAJOR_MINOR_VERSION})

# --------------------------------
Expand Down
7 changes: 4 additions & 3 deletions urdf_parser/include/urdf_parser/urdf_parser.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@

#include <string>
#include <map>
#include <tinyxml.h>
#include <tinyxml2.h>
#include <urdf_model/model.h>
#include <urdf_model/color.h>
#include <urdf_world/types.h>
Expand All @@ -48,18 +48,19 @@

#include "exportdecl.h"

using TiXmlDocument = tinyxml2::XMLDocument;
using TiXmlElement = tinyxml2::XMLElement;

namespace urdf_export_helpers {

URDFDOM_DLLAPI std::string values2str(unsigned int count, const double *values, double (*conv)(double) = NULL);
URDFDOM_DLLAPI std::string values2str(urdf::Vector3 vec);
URDFDOM_DLLAPI std::string values2str(urdf::Rotation rot);
URDFDOM_DLLAPI std::string values2str(urdf::Color c);
URDFDOM_DLLAPI std::string values2str(double d);

}

namespace urdf{

URDFDOM_DLLAPI ModelInterfaceSharedPtr parseURDF(const std::string &xml_string);
URDFDOM_DLLAPI ModelInterfaceSharedPtr parseURDFFile(const std::string &path);
URDFDOM_DLLAPI TiXmlDocument* exportURDF(ModelInterfaceSharedPtr &model);
Expand Down
80 changes: 38 additions & 42 deletions urdf_parser/src/joint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,16 @@

/* Author: John Hsu */

#include <console_bridge/console.h>
#include <tinyxml2.h>
#include <urdf_model/joint.h>
#include <urdf_parser/urdf_parser.h>

#include <sstream>
#include <stdexcept>
#include <string>
#include <urdf_model/joint.h>
#include <console_bridge/console.h>
#include <tinyxml.h>
#include <urdf_parser/urdf_parser.h>

#include "xml_helpers.h"

namespace urdf{

Expand Down Expand Up @@ -639,46 +642,42 @@ bool exportPose(Pose &pose, TiXmlElement* xml);

bool exportJointDynamics(JointDynamics &jd, TiXmlElement* xml)
{
TiXmlElement *dynamics_xml = new TiXmlElement("dynamics");
dynamics_xml->SetAttribute("damping", urdf_export_helpers::values2str(jd.damping) );
dynamics_xml->SetAttribute("friction", urdf_export_helpers::values2str(jd.friction) );
xml->LinkEndChild(dynamics_xml);
auto * dynamics_xml = xmlAppendChild(xml, "dynamics");
dynamics_xml->SetAttribute("damping", jd.damping );
dynamics_xml->SetAttribute("friction", jd.friction );
return true;
}

bool exportJointLimits(JointLimits &jl, TiXmlElement* xml)
{
TiXmlElement *limit_xml = new TiXmlElement("limit");
limit_xml->SetAttribute("effort", urdf_export_helpers::values2str(jl.effort) );
limit_xml->SetAttribute("velocity", urdf_export_helpers::values2str(jl.velocity) );
limit_xml->SetAttribute("lower", urdf_export_helpers::values2str(jl.lower) );
limit_xml->SetAttribute("upper", urdf_export_helpers::values2str(jl.upper) );
xml->LinkEndChild(limit_xml);
auto * limit_xml = xmlAppendChild(xml, "limit");
limit_xml->SetAttribute("effort", jl.effort);
limit_xml->SetAttribute("velocity", jl.velocity );
limit_xml->SetAttribute("lower", jl.lower );
limit_xml->SetAttribute("upper", jl.upper );
return true;
}

bool exportJointSafety(JointSafety &js, TiXmlElement* xml)
{
TiXmlElement *safety_xml = new TiXmlElement("safety_controller");
safety_xml->SetAttribute("k_position", urdf_export_helpers::values2str(js.k_position) );
safety_xml->SetAttribute("k_velocity", urdf_export_helpers::values2str(js.k_velocity) );
safety_xml->SetAttribute("soft_lower_limit", urdf_export_helpers::values2str(js.soft_lower_limit) );
safety_xml->SetAttribute("soft_upper_limit", urdf_export_helpers::values2str(js.soft_upper_limit) );
xml->LinkEndChild(safety_xml);
auto * safety_xml = xmlAppendChild(xml, "safety_controller");
safety_xml->SetAttribute("k_position", js.k_position );
safety_xml->SetAttribute("k_velocity", js.k_velocity );
safety_xml->SetAttribute("soft_lower_limit", js.soft_lower_limit );
safety_xml->SetAttribute("soft_upper_limit", js.soft_upper_limit );
return true;
}

bool exportJointCalibration(JointCalibration &jc, TiXmlElement* xml)
{
if (jc.falling || jc.rising)
{
TiXmlElement *calibration_xml = new TiXmlElement("calibration");
auto * calibration_xml = xmlAppendChild(xml, "calibration");
if (jc.falling)
calibration_xml->SetAttribute("falling", urdf_export_helpers::values2str(*jc.falling) );
calibration_xml->SetAttribute("falling", *jc.falling );
if (jc.rising)
calibration_xml->SetAttribute("rising", urdf_export_helpers::values2str(*jc.rising) );
calibration_xml->SetAttribute("rising", *jc.rising );
//calibration_xml->SetAttribute("reference_position", urdf_export_helpers::values2str(jc.reference_position) );
xml->LinkEndChild(calibration_xml);
}
return true;
}
Expand All @@ -687,19 +686,20 @@ bool exportJointMimic(JointMimic &jm, TiXmlElement* xml)
{
if (!jm.joint_name.empty())
{
TiXmlElement *mimic_xml = new TiXmlElement("mimic");
mimic_xml->SetAttribute("offset", urdf_export_helpers::values2str(jm.offset) );
mimic_xml->SetAttribute("multiplier", urdf_export_helpers::values2str(jm.multiplier) );
mimic_xml->SetAttribute("joint", jm.joint_name );
xml->LinkEndChild(mimic_xml);
auto * mimic_xml = xmlAppendChild(xml, "mimic");

mimic_xml->SetAttribute("offset", jm.offset );
mimic_xml->SetAttribute("multiplier", jm.multiplier );
mimic_xml->SetAttribute("joint", jm.joint_name.c_str() );
}
return true;
}

bool exportJoint(Joint &joint, TiXmlElement* xml)
{
TiXmlElement * joint_xml = new TiXmlElement("joint");
joint_xml->SetAttribute("name", joint.name);
auto * joint_xml = xmlAppendChild(xml, "joint");

joint_xml->SetAttribute("name", joint.name.c_str());
if (joint.type == urdf::Joint::PLANAR)
joint_xml->SetAttribute("type", "planar");
else if (joint.type == urdf::Joint::FLOATING)
Expand All @@ -719,19 +719,16 @@ bool exportJoint(Joint &joint, TiXmlElement* xml)
exportPose(joint.parent_to_joint_origin_transform, joint_xml);

// axis
TiXmlElement * axis_xml = new TiXmlElement("axis");
axis_xml->SetAttribute("xyz", urdf_export_helpers::values2str(joint.axis));
joint_xml->LinkEndChild(axis_xml);
auto * axis_xml = xmlAppendChild(joint_xml, "axis");
axis_xml->SetAttribute("xyz", urdf_export_helpers::values2str(joint.axis).c_str());

// parent
TiXmlElement * parent_xml = new TiXmlElement("parent");
parent_xml->SetAttribute("link", joint.parent_link_name);
joint_xml->LinkEndChild(parent_xml);
// parent
auto * parent_xml = xmlAppendChild(joint_xml, "parent");
parent_xml->SetAttribute("link", joint.parent_link_name.c_str());

// child
TiXmlElement * child_xml = new TiXmlElement("child");
child_xml->SetAttribute("link", joint.child_link_name);
joint_xml->LinkEndChild(child_xml);
auto * child_xml = xmlAppendChild(joint_xml, "child");
child_xml->SetAttribute("link", joint.child_link_name.c_str());

if (joint.dynamics)
exportJointDynamics(*(joint.dynamics), joint_xml);
Expand All @@ -744,7 +741,6 @@ bool exportJoint(Joint &joint, TiXmlElement* xml)
if (joint.mimic)
exportJointMimic(*(joint.mimic), joint_xml);

xml->LinkEndChild(joint_xml);
return true;
}

Expand Down
Loading

0 comments on commit d88bc41

Please sign in to comment.