From 482763247d7bac0e31df7259e0b31719dc69522d Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Wed, 20 Dec 2023 14:03:37 +0000 Subject: [PATCH] Properly export parsePoseInternal to make Windows happy. Signed-off-by: Chris Lalancette --- urdf_parser/src/joint.cpp | 4 +-- urdf_parser/src/link.cpp | 4 +-- urdf_parser/src/pose.cpp | 2 ++ urdf_parser/src/pose.hpp | 44 +++++++++++++++++++++++++++++++++ urdf_parser/src/urdf_sensor.cpp | 4 +-- 5 files changed, 52 insertions(+), 6 deletions(-) create mode 100644 urdf_parser/src/pose.hpp diff --git a/urdf_parser/src/joint.cpp b/urdf_parser/src/joint.cpp index 614c44b6..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 parsePoseInternal(Pose &pose, tinyxml2::XMLElement* xml); +namespace urdf{ bool parseJointDynamics(JointDynamics &jd, tinyxml2::XMLElement* config) { diff --git a/urdf_parser/src/link.cpp b/urdf_parser/src/link.cpp index 483cf00d..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 parsePoseInternal(Pose &pose, tinyxml2::XMLElement* xml); +namespace urdf{ bool parseMaterial(Material &material, tinyxml2::XMLElement *config, bool only_name_is_ok) { diff --git a/urdf_parser/src/pose.cpp b/urdf_parser/src/pose.cpp index 85c4ec97..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)) 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 f9588235..b9ac592b 100644 --- a/urdf_parser/src/urdf_sensor.cpp +++ b/urdf_parser/src/urdf_sensor.cpp @@ -47,9 +47,9 @@ #include -namespace urdf{ +#include "./pose.hpp" -bool parsePoseInternal(Pose &pose, tinyxml2::XMLElement* xml); +namespace urdf{ bool parseCameraInternal(Camera &camera, tinyxml2::XMLElement* config) {