Skip to content

Commit

Permalink
Remove 'using tinyxml2'
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Nov 29, 2023
1 parent 06a18de commit 2f45917
Show file tree
Hide file tree
Showing 8 changed files with 186 additions and 195 deletions.
24 changes: 11 additions & 13 deletions urdf_parser/include/urdf_parser/urdf_parser.h
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
Expand All @@ -17,7 +17,7 @@
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
Expand Down Expand Up @@ -51,8 +51,6 @@

#include "exportdecl.h"

using namespace tinyxml2;

namespace urdf_export_helpers {

URDFDOM_DLLAPI std::string values2str(unsigned int count, const double *values, double (*conv)(double) = NULL);
Expand Down Expand Up @@ -145,13 +143,13 @@ namespace urdf{

URDFDOM_DLLAPI ModelInterfaceSharedPtr parseURDF(const std::string &xml_string);
URDFDOM_DLLAPI ModelInterfaceSharedPtr parseURDFFile(const std::string &path);
URDFDOM_DLLAPI XMLDocument* exportURDF(ModelInterfaceSharedPtr &model);
URDFDOM_DLLAPI XMLDocument* exportURDF(const ModelInterface &model);
URDFDOM_DLLAPI bool parsePose(Pose&, XMLElement*);
URDFDOM_DLLAPI bool parseCamera(Camera&, XMLElement*);
URDFDOM_DLLAPI bool parseRay(Ray&, XMLElement*);
URDFDOM_DLLAPI bool parseSensor(Sensor&, XMLElement*);
URDFDOM_DLLAPI bool parseModelState(ModelState&, XMLElement*);
URDFDOM_DLLAPI tinyxml2::XMLDocument* exportURDF(ModelInterfaceSharedPtr &model);
URDFDOM_DLLAPI tinyxml2::XMLDocument* exportURDF(const ModelInterface &model);
URDFDOM_DLLAPI bool parsePose(Pose&, tinyxml2::XMLElement*);
URDFDOM_DLLAPI bool parseCamera(Camera&, tinyxml2::XMLElement*);
URDFDOM_DLLAPI bool parseRay(Ray&, tinyxml2::XMLElement*);
URDFDOM_DLLAPI bool parseSensor(Sensor&, tinyxml2::XMLElement*);
URDFDOM_DLLAPI bool parseModelState(ModelState&, tinyxml2::XMLElement*);
}

#endif
84 changes: 42 additions & 42 deletions urdf_parser/src/joint.cpp
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
/*********************************************************************
* Software Ligcense Agreement (BSD License)
*
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
Expand All @@ -17,7 +17,7 @@
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
Expand Down Expand Up @@ -45,9 +45,9 @@

namespace urdf{

bool parsePose(Pose &pose, XMLElement* xml);
bool parsePose(Pose &pose, tinyxml2::XMLElement* xml);

bool parseJointDynamics(JointDynamics &jd, XMLElement* config)
bool parseJointDynamics(JointDynamics &jd, tinyxml2::XMLElement* config)
{
jd.clear();

Expand Down Expand Up @@ -94,7 +94,7 @@ bool parseJointDynamics(JointDynamics &jd, XMLElement* config)
}
}

bool parseJointLimits(JointLimits &jl, XMLElement* config)
bool parseJointLimits(JointLimits &jl, tinyxml2::XMLElement* config)
{
jl.clear();

Expand Down Expand Up @@ -165,7 +165,7 @@ bool parseJointLimits(JointLimits &jl, XMLElement* config)
return true;
}

bool parseJointSafety(JointSafety &js, XMLElement* config)
bool parseJointSafety(JointSafety &js, tinyxml2::XMLElement* config)
{
js.clear();

Expand Down Expand Up @@ -239,7 +239,7 @@ bool parseJointSafety(JointSafety &js, XMLElement* config)
return true;
}

bool parseJointCalibration(JointCalibration &jc, XMLElement* config)
bool parseJointCalibration(JointCalibration &jc, tinyxml2::XMLElement* config)
{
jc.clear();

Expand Down Expand Up @@ -280,7 +280,7 @@ bool parseJointCalibration(JointCalibration &jc, XMLElement* config)
return true;
}

bool parseJointMimic(JointMimic &jm, XMLElement* config)
bool parseJointMimic(JointMimic &jm, tinyxml2::XMLElement* config)
{
jm.clear();

Expand All @@ -294,14 +294,14 @@ bool parseJointMimic(JointMimic &jm, XMLElement* config)
}
else
jm.joint_name = joint_name_str;

// Get mimic multiplier
const char* multiplier_str = config->Attribute("multiplier");

if (multiplier_str == NULL)
{
CONSOLE_BRIDGE_logDebug("urdfdom.joint_mimic: no multiplier, using default value of 1");
jm.multiplier = 1;
jm.multiplier = 1;
}
else
{
Expand All @@ -313,7 +313,7 @@ bool parseJointMimic(JointMimic &jm, XMLElement* config)
}
}


// Get mimic offset
const char* offset_str = config->Attribute("offset");
if (offset_str == NULL)
Expand All @@ -334,7 +334,7 @@ bool parseJointMimic(JointMimic &jm, XMLElement* config)
return true;
}

bool parseJoint(Joint &joint, XMLElement* config)
bool parseJoint(Joint &joint, tinyxml2::XMLElement* config)
{
joint.clear();

Expand All @@ -348,7 +348,7 @@ bool parseJoint(Joint &joint, XMLElement* config)
joint.name = name;

// Get transform from Parent Link to Joint Frame
XMLElement *origin_xml = config->FirstChildElement("origin");
tinyxml2::XMLElement *origin_xml = config->FirstChildElement("origin");
if (!origin_xml)
{
CONSOLE_BRIDGE_logDebug("urdfdom: Joint [%s] missing origin tag under parent describing transform from Parent Link to Joint Frame, (using Identity transform).", joint.name.c_str());
Expand All @@ -365,7 +365,7 @@ bool parseJoint(Joint &joint, XMLElement* config)
}

// Get Parent Link
XMLElement *parent_xml = config->FirstChildElement("parent");
tinyxml2::XMLElement *parent_xml = config->FirstChildElement("parent");
if (parent_xml)
{
const char *pname = parent_xml->Attribute("link");
Expand All @@ -380,7 +380,7 @@ bool parseJoint(Joint &joint, XMLElement* config)
}

// Get Child Link
XMLElement *child_xml = config->FirstChildElement("child");
tinyxml2::XMLElement *child_xml = config->FirstChildElement("child");
if (child_xml)
{
const char *pname = child_xml->Attribute("link");
Expand All @@ -401,7 +401,7 @@ bool parseJoint(Joint &joint, XMLElement* config)
CONSOLE_BRIDGE_logError("joint [%s] has no type, check to see if it's a reference.", joint.name.c_str());
return false;
}

std::string type_str = type_char;
if (type_str == "planar")
joint.type = Joint::PLANAR;
Expand All @@ -425,7 +425,7 @@ bool parseJoint(Joint &joint, XMLElement* config)
if (joint.type != Joint::FLOATING && joint.type != Joint::FIXED)
{
// axis
XMLElement *axis_xml = config->FirstChildElement("axis");
tinyxml2::XMLElement *axis_xml = config->FirstChildElement("axis");
if (!axis_xml){
CONSOLE_BRIDGE_logDebug("urdfdom: no axis element for Joint link [%s], defaulting to (1,0,0) axis", joint.name.c_str());
joint.axis = Vector3(1.0, 0.0, 0.0);
Expand All @@ -445,7 +445,7 @@ bool parseJoint(Joint &joint, XMLElement* config)
}

// Get limit
XMLElement *limit_xml = config->FirstChildElement("limit");
tinyxml2::XMLElement *limit_xml = config->FirstChildElement("limit");
if (limit_xml)
{
joint.limits.reset(new JointLimits());
Expand All @@ -463,12 +463,12 @@ bool parseJoint(Joint &joint, XMLElement* config)
}
else if (joint.type == Joint::PRISMATIC)
{
CONSOLE_BRIDGE_logError("Joint [%s] is of type PRISMATIC without limits", joint.name.c_str());
CONSOLE_BRIDGE_logError("Joint [%s] is of type PRISMATIC without limits", joint.name.c_str());
return false;
}

// Get safety
XMLElement *safety_xml = config->FirstChildElement("safety_controller");
tinyxml2::XMLElement *safety_xml = config->FirstChildElement("safety_controller");
if (safety_xml)
{
joint.safety.reset(new JointSafety());
Expand All @@ -481,7 +481,7 @@ bool parseJoint(Joint &joint, XMLElement* config)
}

// Get calibration
XMLElement *calibration_xml = config->FirstChildElement("calibration");
tinyxml2::XMLElement *calibration_xml = config->FirstChildElement("calibration");
if (calibration_xml)
{
joint.calibration.reset(new JointCalibration());
Expand All @@ -494,7 +494,7 @@ bool parseJoint(Joint &joint, XMLElement* config)
}

// Get Joint Mimic
XMLElement *mimic_xml = config->FirstChildElement("mimic");
tinyxml2::XMLElement *mimic_xml = config->FirstChildElement("mimic");
if (mimic_xml)
{
joint.mimic.reset(new JointMimic());
Expand All @@ -507,7 +507,7 @@ bool parseJoint(Joint &joint, XMLElement* config)
}

// Get Dynamics
XMLElement *prop_xml = config->FirstChildElement("dynamics");
tinyxml2::XMLElement *prop_xml = config->FirstChildElement("dynamics");
if (prop_xml)
{
joint.dynamics.reset(new JointDynamics());
Expand All @@ -524,20 +524,20 @@ bool parseJoint(Joint &joint, XMLElement* config)


/* exports */
bool exportPose(Pose &pose, XMLElement* xml);
bool exportPose(Pose &pose, tinyxml2::XMLElement* xml);

bool exportJointDynamics(JointDynamics &jd, XMLElement* xml)
bool exportJointDynamics(JointDynamics &jd, tinyxml2::XMLElement* xml)
{
XMLElement *dynamics_xml = xml->InsertNewChildElement("dynamics");
tinyxml2::XMLElement *dynamics_xml = xml->InsertNewChildElement("dynamics");
dynamics_xml->SetAttribute("damping", urdf_export_helpers::values2str(jd.damping).c_str() );
dynamics_xml->SetAttribute("friction", urdf_export_helpers::values2str(jd.friction).c_str() );
xml->LinkEndChild(dynamics_xml);
return true;
}

bool exportJointLimits(JointLimits &jl, XMLElement* xml)
bool exportJointLimits(JointLimits &jl, tinyxml2::XMLElement* xml)
{
XMLElement *limit_xml = xml->InsertNewChildElement("limit");
tinyxml2::XMLElement *limit_xml = xml->InsertNewChildElement("limit");
limit_xml->SetAttribute("effort", urdf_export_helpers::values2str(jl.effort).c_str());
limit_xml->SetAttribute("velocity", urdf_export_helpers::values2str(jl.velocity).c_str());
limit_xml->SetAttribute("lower", urdf_export_helpers::values2str(jl.lower).c_str());
Expand All @@ -546,9 +546,9 @@ bool exportJointLimits(JointLimits &jl, XMLElement* xml)
return true;
}

bool exportJointSafety(JointSafety &js, XMLElement* xml)
bool exportJointSafety(JointSafety &js, tinyxml2::XMLElement* xml)
{
XMLElement *safety_xml = xml->InsertNewChildElement("safety_controller");
tinyxml2::XMLElement *safety_xml = xml->InsertNewChildElement("safety_controller");
safety_xml->SetAttribute("k_position", urdf_export_helpers::values2str(js.k_position).c_str());
safety_xml->SetAttribute("k_velocity", urdf_export_helpers::values2str(js.k_velocity).c_str());
safety_xml->SetAttribute("soft_lower_limit", urdf_export_helpers::values2str(js.soft_lower_limit).c_str());
Expand All @@ -557,11 +557,11 @@ bool exportJointSafety(JointSafety &js, XMLElement* xml)
return true;
}

bool exportJointCalibration(JointCalibration &jc, XMLElement* xml)
bool exportJointCalibration(JointCalibration &jc, tinyxml2::XMLElement* xml)
{
if (jc.falling || jc.rising)
{
XMLElement *calibration_xml = xml->InsertNewChildElement("calibration");
tinyxml2::XMLElement *calibration_xml = xml->InsertNewChildElement("calibration");
if (jc.falling)
calibration_xml->SetAttribute("falling", urdf_export_helpers::values2str(*jc.falling).c_str());
if (jc.rising)
Expand All @@ -572,11 +572,11 @@ bool exportJointCalibration(JointCalibration &jc, XMLElement* xml)
return true;
}

bool exportJointMimic(JointMimic &jm, XMLElement* xml)
bool exportJointMimic(JointMimic &jm, tinyxml2::XMLElement* xml)
{
if (!jm.joint_name.empty())
{
XMLElement *mimic_xml = xml->InsertNewChildElement("mimic");
tinyxml2::XMLElement *mimic_xml = xml->InsertNewChildElement("mimic");
mimic_xml->SetAttribute("offset", urdf_export_helpers::values2str(jm.offset).c_str());
mimic_xml->SetAttribute("multiplier", urdf_export_helpers::values2str(jm.multiplier).c_str());
mimic_xml->SetAttribute("joint", jm.joint_name.c_str());
Expand All @@ -585,9 +585,9 @@ bool exportJointMimic(JointMimic &jm, XMLElement* xml)
return true;
}

bool exportJoint(Joint &joint, XMLElement* xml)
bool exportJoint(Joint &joint, tinyxml2::XMLElement* xml)
{
XMLElement * joint_xml = xml->InsertNewChildElement("joint");
tinyxml2::XMLElement * joint_xml = xml->InsertNewChildElement("joint");
joint_xml->SetAttribute("name", joint.name.c_str());
if (joint.type == urdf::Joint::PLANAR)
joint_xml->SetAttribute("type", "planar");
Expand All @@ -608,17 +608,17 @@ bool exportJoint(Joint &joint, XMLElement* xml)
exportPose(joint.parent_to_joint_origin_transform, joint_xml);

// axis
XMLElement * axis_xml = joint_xml->InsertNewChildElement("axis");
tinyxml2::XMLElement * axis_xml = joint_xml->InsertNewChildElement("axis");
axis_xml->SetAttribute("xyz", urdf_export_helpers::values2str(joint.axis).c_str());
joint_xml->LinkEndChild(axis_xml);

// parent
XMLElement * parent_xml = joint_xml->InsertNewChildElement("parent");
// parent
tinyxml2::XMLElement * parent_xml = joint_xml->InsertNewChildElement("parent");
parent_xml->SetAttribute("link", joint.parent_link_name.c_str());
joint_xml->LinkEndChild(parent_xml);

// child
XMLElement * child_xml = joint_xml->InsertNewChildElement("child");
tinyxml2::XMLElement * child_xml = joint_xml->InsertNewChildElement("child");
child_xml->SetAttribute("link", joint.child_link_name.c_str());
joint_xml->LinkEndChild(child_xml);

Expand Down
Loading

0 comments on commit 2f45917

Please sign in to comment.