From cc63d5698042357f89b189997507d44fbed31503 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Wed, 20 Dec 2023 11:50:56 -0500 Subject: [PATCH] Deprecate the APIs that we think are unused. (#191) * Deprecate the APIs that we think are unused. In an earlier commit, we changed from tinyxml -> tinyxml2 in the public API because we thought that there were no users of these APIs. Codify that here by marking these APIs as deprecated; if a user comes along and says that they are actually using it, we can undeprecated it. Note that in order to avoid deprecations from within the library, I had to add a bit of additional indirection here. If we remove the APIs in the future, we can also remove this indirection. * Properly export parsePoseInternal to make Windows happy. Signed-off-by: Chris Lalancette --- urdf_parser/include/urdf_parser/urdf_parser.h | 14 ++++++ urdf_parser/src/joint.cpp | 6 +-- urdf_parser/src/link.cpp | 10 ++--- urdf_parser/src/model.cpp | 10 ++++- urdf_parser/src/pose.cpp | 9 +++- urdf_parser/src/pose.hpp | 44 +++++++++++++++++++ urdf_parser/src/urdf_sensor.cpp | 24 +++++++--- 7 files changed, 99 insertions(+), 18 deletions(-) create mode 100644 urdf_parser/src/pose.hpp diff --git a/urdf_parser/include/urdf_parser/urdf_parser.h b/urdf_parser/include/urdf_parser/urdf_parser.h index 0ea27df1..240e9df3 100644 --- a/urdf_parser/include/urdf_parser/urdf_parser.h +++ b/urdf_parser/include/urdf_parser/urdf_parser.h @@ -149,12 +149,26 @@ namespace urdf{ URDFDOM_DLLAPI ModelInterfaceSharedPtr parseURDF(const std::string &xml_string); URDFDOM_DLLAPI ModelInterfaceSharedPtr parseURDFFile(const std::string &path); + + [[deprecated("File an issue at https://github.com/ros/urdfdom if you rely on this")]] URDFDOM_DLLAPI tinyxml2::XMLDocument* exportURDF(ModelInterfaceSharedPtr &model); + + [[deprecated("File an issue at https://github.com/ros/urdfdom if you rely on this")]] URDFDOM_DLLAPI tinyxml2::XMLDocument* exportURDF(const ModelInterface &model); + + [[deprecated("File an issue at https://github.com/ros/urdfdom if you rely on this")]] URDFDOM_DLLAPI bool parsePose(Pose&, tinyxml2::XMLElement*); + + [[deprecated("File an issue at https://github.com/ros/urdfdom if you rely on this")]] URDFDOM_DLLAPI bool parseCamera(Camera&, tinyxml2::XMLElement*); + + [[deprecated("File an issue at https://github.com/ros/urdfdom if you rely on this")]] URDFDOM_DLLAPI bool parseRay(Ray&, tinyxml2::XMLElement*); + + [[deprecated("File an issue at https://github.com/ros/urdfdom if you rely on this")]] URDFDOM_DLLAPI bool parseSensor(Sensor&, tinyxml2::XMLElement*); + + [[deprecated("File an issue at https://github.com/ros/urdfdom if you rely on this")]] URDFDOM_DLLAPI bool parseModelState(ModelState&, tinyxml2::XMLElement*); } diff --git a/urdf_parser/src/joint.cpp b/urdf_parser/src/joint.cpp index 7668350f..4269419a 100644 --- a/urdf_parser/src/joint.cpp +++ b/urdf_parser/src/joint.cpp @@ -43,9 +43,9 @@ #include #include -namespace urdf{ +#include "./pose.hpp" -bool parsePose(Pose &pose, tinyxml2::XMLElement* xml); +namespace urdf{ bool parseJointDynamics(JointDynamics &jd, tinyxml2::XMLElement* config) { @@ -356,7 +356,7 @@ bool parseJoint(Joint &joint, tinyxml2::XMLElement* config) } else { - if (!parsePose(joint.parent_to_joint_origin_transform, origin_xml)) + if (!parsePoseInternal(joint.parent_to_joint_origin_transform, origin_xml)) { joint.parent_to_joint_origin_transform.clear(); CONSOLE_BRIDGE_logError("Malformed parent origin element for joint [%s]", joint.name.c_str()); diff --git a/urdf_parser/src/link.cpp b/urdf_parser/src/link.cpp index 85dafd44..ab83b5d3 100644 --- a/urdf_parser/src/link.cpp +++ b/urdf_parser/src/link.cpp @@ -48,9 +48,9 @@ #include #include -namespace urdf{ +#include "./pose.hpp" -bool parsePose(Pose &pose, tinyxml2::XMLElement* xml); +namespace urdf{ bool parseMaterial(Material &material, tinyxml2::XMLElement *config, bool only_name_is_ok) { @@ -274,7 +274,7 @@ bool parseInertial(Inertial &i, tinyxml2::XMLElement *config) tinyxml2::XMLElement *o = config->FirstChildElement("origin"); if (o) { - if (!parsePose(i.origin, o)) + if (!parsePoseInternal(i.origin, o)) return false; } @@ -353,7 +353,7 @@ bool parseVisual(Visual &vis, tinyxml2::XMLElement *config) // Origin tinyxml2::XMLElement *o = config->FirstChildElement("origin"); if (o) { - if (!parsePose(vis.origin, o)) + if (!parsePoseInternal(vis.origin, o)) return false; } @@ -395,7 +395,7 @@ bool parseCollision(Collision &col, tinyxml2::XMLElement* config) // Origin tinyxml2::XMLElement *o = config->FirstChildElement("origin"); if (o) { - if (!parsePose(col.origin, o)) + if (!parsePoseInternal(col.origin, o)) return false; } diff --git a/urdf_parser/src/model.cpp b/urdf_parser/src/model.cpp index fb49ecca..5236668a 100644 --- a/urdf_parser/src/model.cpp +++ b/urdf_parser/src/model.cpp @@ -273,7 +273,8 @@ ModelInterfaceSharedPtr parseURDF(const std::string &xml_string) bool exportMaterial(Material &material, tinyxml2::XMLElement *config); bool exportLink(Link &link, tinyxml2::XMLElement *config); bool exportJoint(Joint &joint, tinyxml2::XMLElement *config); -tinyxml2::XMLDocument* exportURDF(const ModelInterface &model) + +tinyxml2::XMLDocument* exportURDFInternal(const ModelInterface &model) { tinyxml2::XMLDocument *doc = new tinyxml2::XMLDocument(); @@ -303,9 +304,14 @@ tinyxml2::XMLDocument* exportURDF(const ModelInterface &model) return doc; } +tinyxml2::XMLDocument* exportURDF(const ModelInterface &model) +{ + return exportURDFInternal(model); +} + tinyxml2::XMLDocument* exportURDF(ModelInterfaceSharedPtr &model) { - return exportURDF(*model); + return exportURDFInternal(*model); } diff --git a/urdf_parser/src/pose.cpp b/urdf_parser/src/pose.cpp index 87479f39..ce6c92b2 100644 --- a/urdf_parser/src/pose.cpp +++ b/urdf_parser/src/pose.cpp @@ -43,6 +43,8 @@ #include #include +#include "./pose.hpp" + namespace urdf_export_helpers { std::string values2str(unsigned int count, const double *values, double (*conv)(double)) @@ -87,7 +89,7 @@ std::string values2str(double d) namespace urdf{ -bool parsePose(Pose &pose, tinyxml2::XMLElement* xml) +bool parsePoseInternal(Pose &pose, tinyxml2::XMLElement* xml) { pose.clear(); if (xml) @@ -119,6 +121,11 @@ bool parsePose(Pose &pose, tinyxml2::XMLElement* xml) return true; } +bool parsePose(Pose &pose, tinyxml2::XMLElement* xml) +{ + return parsePoseInternal(pose, xml); +} + bool exportPose(Pose &pose, tinyxml2::XMLElement* xml) { tinyxml2::XMLElement* origin = xml->GetDocument()->NewElement("origin"); diff --git a/urdf_parser/src/pose.hpp b/urdf_parser/src/pose.hpp new file mode 100644 index 00000000..cadc1832 --- /dev/null +++ b/urdf_parser/src/pose.hpp @@ -0,0 +1,44 @@ +/********************************************************************* +* 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 +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * 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 +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Wim Meeussen, John Hsu */ + +#include +#include + +namespace urdf { + +URDFDOM_DLLAPI bool parsePoseInternal(Pose &pose, tinyxml2::XMLElement* xml); + +} diff --git a/urdf_parser/src/urdf_sensor.cpp b/urdf_parser/src/urdf_sensor.cpp index 8332920c..b9ac592b 100644 --- a/urdf_parser/src/urdf_sensor.cpp +++ b/urdf_parser/src/urdf_sensor.cpp @@ -47,11 +47,11 @@ #include -namespace urdf{ +#include "./pose.hpp" -bool parsePose(Pose &pose, tinyxml2::XMLElement* xml); +namespace urdf{ -bool parseCamera(Camera &camera, tinyxml2::XMLElement* config) +bool parseCameraInternal(Camera &camera, tinyxml2::XMLElement* config) { camera.clear(); camera.type = VisualSensor::CAMERA; @@ -173,7 +173,12 @@ bool parseCamera(Camera &camera, tinyxml2::XMLElement* config) return true; } -bool parseRay(Ray &ray, tinyxml2::XMLElement* config) +bool parseCamera(Camera &camera, tinyxml2::XMLElement* config) +{ + return parseCameraInternal(camera, config); +} + +bool parseRayInternal(Ray &ray, tinyxml2::XMLElement* config) { ray.clear(); ray.type = VisualSensor::RAY; @@ -292,6 +297,11 @@ bool parseRay(Ray &ray, tinyxml2::XMLElement* config) return false; } +bool parseRay(Ray &ray, tinyxml2::XMLElement* config) +{ + return parseRayInternal(ray, config); +} + VisualSensorSharedPtr parseVisualSensor(tinyxml2::XMLElement *g) { VisualSensorSharedPtr visual_sensor; @@ -303,7 +313,7 @@ VisualSensorSharedPtr parseVisualSensor(tinyxml2::XMLElement *g) Camera *camera = new Camera(); visual_sensor.reset(camera); sensor_xml = g->FirstChildElement("camera"); - if (!parseCamera(*camera, sensor_xml)) + if (!parseCameraInternal(*camera, sensor_xml)) visual_sensor.reset(); } else if (g->FirstChildElement("ray")) @@ -311,7 +321,7 @@ VisualSensorSharedPtr parseVisualSensor(tinyxml2::XMLElement *g) Ray *ray = new Ray(); visual_sensor.reset(ray); sensor_xml = g->FirstChildElement("ray"); - if (!parseRay(*ray, sensor_xml)) + if (!parseRayInternal(*ray, sensor_xml)) visual_sensor.reset(); } else @@ -347,7 +357,7 @@ bool parseSensor(Sensor &sensor, tinyxml2::XMLElement* config) tinyxml2::XMLElement *o = config->FirstChildElement("origin"); if (o) { - if (!parsePose(sensor.origin, o)) + if (!parsePoseInternal(sensor.origin, o)) return false; }