Skip to content

Commit 4827632

Browse files
committed
Properly export parsePoseInternal to make Windows happy.
Signed-off-by: Chris Lalancette <clalancette@gmail.com>
1 parent f6830b9 commit 4827632

File tree

5 files changed

+52
-6
lines changed

5 files changed

+52
-6
lines changed

urdf_parser/src/joint.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,9 +43,9 @@
4343
#include <tinyxml2.h>
4444
#include <urdf_parser/urdf_parser.h>
4545

46-
namespace urdf{
46+
#include "./pose.hpp"
4747

48-
bool parsePoseInternal(Pose &pose, tinyxml2::XMLElement* xml);
48+
namespace urdf{
4949

5050
bool parseJointDynamics(JointDynamics &jd, tinyxml2::XMLElement* config)
5151
{

urdf_parser/src/link.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -48,9 +48,9 @@
4848
#include <tinyxml2.h>
4949
#include <console_bridge/console.h>
5050

51-
namespace urdf{
51+
#include "./pose.hpp"
5252

53-
bool parsePoseInternal(Pose &pose, tinyxml2::XMLElement* xml);
53+
namespace urdf{
5454

5555
bool parseMaterial(Material &material, tinyxml2::XMLElement *config, bool only_name_is_ok)
5656
{

urdf_parser/src/pose.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,8 @@
4343
#include <tinyxml2.h>
4444
#include <urdf_parser/urdf_parser.h>
4545

46+
#include "./pose.hpp"
47+
4648
namespace urdf_export_helpers {
4749

4850
std::string values2str(unsigned int count, const double *values, double (*conv)(double))

urdf_parser/src/pose.hpp

Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
/*********************************************************************
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2008, Willow Garage, Inc.
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of the Willow Garage nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*********************************************************************/
34+
35+
/* Author: Wim Meeussen, John Hsu */
36+
37+
#include <urdf_model/pose.h>
38+
#include <tinyxml2.h>
39+
40+
namespace urdf {
41+
42+
URDFDOM_DLLAPI bool parsePoseInternal(Pose &pose, tinyxml2::XMLElement* xml);
43+
44+
}

urdf_parser/src/urdf_sensor.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -47,9 +47,9 @@
4747

4848
#include <urdf_parser/urdf_parser.h>
4949

50-
namespace urdf{
50+
#include "./pose.hpp"
5151

52-
bool parsePoseInternal(Pose &pose, tinyxml2::XMLElement* xml);
52+
namespace urdf{
5353

5454
bool parseCameraInternal(Camera &camera, tinyxml2::XMLElement* config)
5555
{

0 commit comments

Comments
 (0)