Skip to content

Commit c75f9b3

Browse files
authored
Fix tf2_bullet dependency export (#428)
* [tf2_bullet] add bullet include path to exports * [tf2_bullet] copyright fix Co-authored-by: Bjar Ne <[email protected]>
1 parent bb565b9 commit c75f9b3

File tree

5 files changed

+42
-8
lines changed

5 files changed

+42
-8
lines changed

tf2_bullet/CMakeLists.txt

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -46,5 +46,4 @@ if(BUILD_TESTING)
4646
endif()
4747

4848
ament_export_include_directories(include)
49-
ament_export_libraries(${PROJECT_NAME})
50-
ament_package()
49+
ament_package(CONFIG_EXTRAS bullet-extras.cmake)

tf2_bullet/bullet-extras.cmake

Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
# Copyright 2021 Open Source Robotics Foundation, Inc.
2+
#
3+
# Redistribution and use in source and binary forms, with or without
4+
# modification, are permitted provided that the following conditions are met:
5+
#
6+
# * Redistributions of source code must retain the above copyright
7+
# notice, this list of conditions and the following disclaimer.
8+
#
9+
# * Redistributions in binary form must reproduce the above copyright
10+
# notice, this list of conditions and the following disclaimer in the
11+
# documentation and/or other materials provided with the distribution.
12+
#
13+
# * Neither the name of the Open Source Robotics Foundation, Inc. nor the names of its
14+
# contributors may be used to endorse or promote products derived from
15+
# this software without specific prior written permission.
16+
#
17+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18+
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19+
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20+
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21+
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22+
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23+
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24+
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25+
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26+
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27+
# POSSIBILITY OF SUCH DAMAGE.
28+
29+
if(WIN32)
30+
set(BULLET_ROOT $ENV{ChocolateyInstall}/lib/bullet)
31+
endif()
32+
find_package(Bullet REQUIRED)
33+
34+
include_directories(SYSTEM ${BULLET_INCLUDE_DIRS})

tf2_bullet/include/tf2_bullet/tf2_bullet.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2008, Willow Garage, Inc. All rights reserved.
1+
// Copyright 2008 Willow Garage, Inc.
22
//
33
// Redistribution and use in source and binary forms, with or without
44
// modification, are permitted provided that the following conditions are met:
@@ -10,7 +10,7 @@
1010
// notice, this list of conditions and the following disclaimer in the
1111
// documentation and/or other materials provided with the distribution.
1212
//
13-
// * Neither the name of the Willo Garage, Inc nor the names of its
13+
// * Neither the name of the Willow Garage, Inc. nor the names of its
1414
// contributors may be used to endorse or promote products derived from
1515
// this software without specific prior written permission.
1616
//

tf2_bullet/include/tf2_bullet/tf2_bullet.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2008, Willow Garage, Inc. All rights reserved.
1+
// Copyright 2008 Willow Garage, Inc.
22
//
33
// Redistribution and use in source and binary forms, with or without
44
// modification, are permitted provided that the following conditions are met:
@@ -10,7 +10,7 @@
1010
// notice, this list of conditions and the following disclaimer in the
1111
// documentation and/or other materials provided with the distribution.
1212
//
13-
// * Neither the name of the Willo Garage, Inc nor the names of its
13+
// * Neither the name of the Willow Garage, Inc. nor the names of its
1414
// contributors may be used to endorse or promote products derived from
1515
// this software without specific prior written permission.
1616
//
@@ -32,6 +32,7 @@
3232
#define TF2_BULLET__TF2_BULLET_HPP_
3333

3434
#include <tf2/convert.h>
35+
#include <LinearMath/btQuaternion.h>
3536
#include <LinearMath/btScalar.h>
3637
#include <LinearMath/btTransform.h>
3738
#include <geometry_msgs/msg/point_stamped.hpp>

tf2_bullet/test/test_tf2_bullet.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2008, Willow Garage, Inc. All rights reserved.
1+
// Copyright 2008 Willow Garage, Inc.
22
//
33
// Redistribution and use in source and binary forms, with or without
44
// modification, are permitted provided that the following conditions are met:
@@ -10,7 +10,7 @@
1010
// notice, this list of conditions and the following disclaimer in the
1111
// documentation and/or other materials provided with the distribution.
1212
//
13-
// * Neither the name of the Willo Garage, Inc nor the names of its
13+
// * Neither the name of the Willow Garage, Inc. nor the names of its
1414
// contributors may be used to endorse or promote products derived from
1515
// this software without specific prior written permission.
1616
//

0 commit comments

Comments
 (0)