Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

use tinyxml2 instead of tinyxml #85

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions bin/joint_limits_from_urdf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
#include <tools/URDFTools.hpp>
#include <base/JointLimits.hpp>
#include <boost/program_options.hpp>
#include <iostream>

using namespace wbc;
using namespace std;
Expand Down
5 changes: 3 additions & 2 deletions src/robot_models/rbdl/RobotModelRBDL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include <rbdl/rbdl_utils.h>
#include <rbdl/addons/urdfreader/urdfreader.h>
#include <base-logging/Logging.hpp>
#include <tinyxml2.h>

using namespace RigidBodyDynamics;

Expand Down Expand Up @@ -49,9 +50,9 @@ bool RobotModelRBDL::configure(const RobotModelConfig& cfg){
if(l.second->inertial)
l.second->inertial->origin.rotation.setFromRPY(0,0,0);
}
TiXmlDocument *doc = urdf::exportURDF(robot_urdf);
tinyxml2::XMLDocument *doc = urdf::exportURDF(robot_urdf);
std::string robot_urdf_file = "/tmp/robot.urdf";
doc->SaveFile(robot_urdf_file);
doc->SaveFile(robot_urdf_file.c_str());

if(!Addons::URDFReadFromFile(robot_urdf_file.c_str(), rbdl_model.get(), cfg.floating_base)){
LOG_ERROR_S << "Unable to parse urdf from file " << robot_urdf_file << std::endl;
Expand Down
6 changes: 4 additions & 2 deletions src/tools/URDFTools.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@
#include <base-logging/Logging.hpp>
#include <urdf_model/link.h>
#include <stack>
#include <iostream>
#include <tinyxml2.h>

namespace wbc {

Expand Down Expand Up @@ -123,8 +125,8 @@ std::vector<std::string> URDFTools::addFloatingBaseToURDF(urdf::ModelInterfaceSh

std::vector<std::string> floating_base_names = {"floating_base_trans_x", "floating_base_trans_y", "floating_base_trans_z",
"floating_base_rot_x", "floating_base_rot_y", "floating_base_rot_z"};
TiXmlDocument *doc = urdf::exportURDF(robot_urdf);
TiXmlPrinter printer;
tinyxml2::XMLDocument *doc = urdf::exportURDF(robot_urdf);
tinyxml2::XMLPrinter printer;
doc->Accept(&printer);
std::string robot_xml_string = printer.CStr();
robot_xml_string.erase(robot_xml_string.find("</robot>"), std::string("</robot>").length());
Expand Down
Loading