Skip to content

Commit 531ca35

Browse files
authored
Deprecate tf2_bullet.h (#412)
Move it to tf2_bullet.hpp instead. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 8df50cd commit 531ca35

File tree

8 files changed

+153
-151
lines changed

8 files changed

+153
-151
lines changed

test_tf2/test/test_buffer_client.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
#include <gtest/gtest.h>
3838

3939
#include <rclcpp/rclcpp.hpp>
40-
#include <tf2_bullet/tf2_bullet.h>
40+
#include <tf2_bullet/tf2_bullet.hpp>
4141
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
4242
#include <tf2_kdl/tf2_kdl.h>
4343
#include <tf2_ros/buffer_client.h>

test_tf2/test/test_convert.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
#include <gtest/gtest.h>
3838
#include <tf2/convert.h>
3939
#include <tf2_kdl/tf2_kdl.h>
40-
#include <tf2_bullet/tf2_bullet.h>
40+
#include <tf2_bullet/tf2_bullet.hpp>
4141
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
4242

4343
TEST(tf2Convert, kdlToBullet)

test_tf2/test/test_tf2_bullet.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929

3030
/** \author Wim Meeussen */
3131

32-
#include <tf2_bullet/tf2_bullet.h>
32+
#include <tf2_bullet/tf2_bullet.hpp>
3333
#include <tf2_ros/buffer.h>
3434
#include <rclcpp/rclcpp.hpp>
3535
#include <gtest/gtest.h>

tf2_bullet/include/tf2_bullet/tf2_bullet.h

Lines changed: 2 additions & 109 deletions
Original file line numberDiff line numberDiff line change
@@ -31,115 +31,8 @@
3131
#ifndef TF2_BULLET__TF2_BULLET_H_
3232
#define TF2_BULLET__TF2_BULLET_H_
3333

34-
#include <tf2/convert.h>
35-
#include <LinearMath/btScalar.h>
36-
#include <LinearMath/btTransform.h>
37-
#include <geometry_msgs/msg/point_stamped.hpp>
38-
#include <tf2_ros/buffer_interface.h>
34+
#warning This header is obsolete, please include tf2_bullet/tf2_bullet.hpp instead
3935

40-
#include <iostream>
41-
42-
#if (BT_BULLET_VERSION <= 282)
43-
// Suppress compilation warning on older versions of Bullet.
44-
// TODO(mjcarroll): Remove this when all platforms have the fix upstream.
45-
inline int bullet_btInfinityMask()
46-
{
47-
return btInfinityMask;
48-
}
49-
#endif
50-
51-
namespace tf2
52-
{
53-
/** \brief Convert a timestamped transform to the equivalent Bullet data type.
54-
* \param t The transform to convert, as a geometry_msgs TransformedStamped message.
55-
* \return The transform message converted to a Bullet btTransform.
56-
*/
57-
inline
58-
btTransform transformToBullet(const geometry_msgs::msg::TransformStamped & t)
59-
{
60-
return btTransform(
61-
btQuaternion(
62-
static_cast < float > (t.transform.rotation.x),
63-
static_cast < float > (t.transform.rotation.y),
64-
static_cast < float > (t.transform.rotation.z),
65-
static_cast < float > (t.transform.rotation.w)),
66-
btVector3(
67-
static_cast < float > (t.transform.translation.x),
68-
static_cast < float > (t.transform.translation.y),
69-
static_cast < float > (t.transform.translation.z)));
70-
}
71-
72-
73-
/** \brief Apply a geometry_msgs TransformStamped to a Bullet-specific Vector3 type.
74-
* This function is a specialization of the doTransform template defined in tf2/convert.h
75-
* \param t_in The vector to transform, as a timestamped Bullet btVector3 data type.
76-
* \param t_out The transformed vector, as a timestamped Bullet btVector3 data type.
77-
* \param transform The timestamped transform to apply, as a TransformStamped message.
78-
*/
79-
template < >
80-
inline
81-
void doTransform(
82-
const tf2::Stamped < btVector3 > & t_in, tf2::Stamped < btVector3 > & t_out,
83-
const geometry_msgs::msg::TransformStamped & transform)
84-
{
85-
t_out =
86-
tf2::Stamped < btVector3 > (
87-
transformToBullet(transform) * t_in,
88-
tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
89-
}
90-
91-
/** \brief Convert a stamped Bullet Vector3 type to a PointStamped message.
92-
* This function is a specialization of the toMsg template defined in tf2/convert.h
93-
* \param in The timestamped Bullet btVector3 to convert.
94-
* \return The vector converted to a PointStamped message.
95-
*/
96-
inline
97-
geometry_msgs::msg::PointStamped toMsg(const tf2::Stamped < btVector3 > & in)
98-
{
99-
geometry_msgs::msg::PointStamped msg;
100-
msg.header.stamp = tf2_ros::toMsg(in.stamp_);
101-
msg.header.frame_id = in.frame_id_;
102-
msg.point.x = in[0];
103-
msg.point.y = in[1];
104-
msg.point.z = in[2];
105-
return msg;
106-
}
107-
108-
/** \brief Convert a PointStamped message type to a stamped Bullet-specific Vector3 type.
109-
* This function is a specialization of the fromMsg template defined in tf2/convert.h
110-
* \param msg The PointStamped message to convert.
111-
* \param out The point converted to a timestamped Bullet Vector3.
112-
*/
113-
inline
114-
void fromMsg(const geometry_msgs::msg::PointStamped & msg, tf2::Stamped < btVector3 > & out)
115-
{
116-
out.stamp_ = tf2_ros::fromMsg(msg.header.stamp);
117-
out.frame_id_ = msg.header.frame_id;
118-
out[0] = static_cast < float > (msg.point.x);
119-
out[1] = static_cast < float > (msg.point.y);
120-
out[2] = static_cast < float > (msg.point.z);
121-
}
122-
123-
124-
/** \brief Apply a geometry_msgs TransformStamped to a Bullet-specific Transform data type.
125-
* This function is a specialization of the doTransform template defined in tf2/convert.h
126-
* \param t_in The frame to transform, as a timestamped Bullet btTransform.
127-
* \param t_out The transformed frame, as a timestamped Bullet btTransform.
128-
* \param transform The timestamped transform to apply, as a TransformStamped message.
129-
*/
130-
template < >
131-
inline
132-
void doTransform(
133-
const tf2::Stamped < btTransform > & t_in, tf2::Stamped < btTransform > & t_out,
134-
const geometry_msgs::msg::TransformStamped & transform)
135-
{
136-
t_out =
137-
tf2::Stamped < btTransform > (
138-
transformToBullet(transform) * t_in,
139-
tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
140-
}
141-
142-
143-
} // namespace tf2
36+
#include <tf2_bullet/tf2_bullet.hpp>
14437

14538
#endif // TF2_BULLET__TF2_BULLET_H_
Lines changed: 145 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,145 @@
1+
// Copyright (c) 2008, Willow Garage, Inc. All rights reserved.
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 Willo Garage, 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+
/** \author Wim Meeussen */
30+
31+
#ifndef TF2_BULLET__TF2_BULLET_HPP_
32+
#define TF2_BULLET__TF2_BULLET_HPP_
33+
34+
#include <tf2/convert.h>
35+
#include <LinearMath/btScalar.h>
36+
#include <LinearMath/btTransform.h>
37+
#include <geometry_msgs/msg/point_stamped.hpp>
38+
#include <tf2_ros/buffer_interface.h>
39+
40+
#include <iostream>
41+
42+
#if (BT_BULLET_VERSION <= 282)
43+
// Suppress compilation warning on older versions of Bullet.
44+
// TODO(mjcarroll): Remove this when all platforms have the fix upstream.
45+
inline int bullet_btInfinityMask()
46+
{
47+
return btInfinityMask;
48+
}
49+
#endif
50+
51+
namespace tf2
52+
{
53+
/** \brief Convert a timestamped transform to the equivalent Bullet data type.
54+
* \param t The transform to convert, as a geometry_msgs TransformedStamped message.
55+
* \return The transform message converted to a Bullet btTransform.
56+
*/
57+
inline
58+
btTransform transformToBullet(const geometry_msgs::msg::TransformStamped & t)
59+
{
60+
return btTransform(
61+
btQuaternion(
62+
static_cast<float>(t.transform.rotation.x),
63+
static_cast<float>(t.transform.rotation.y),
64+
static_cast<float>(t.transform.rotation.z),
65+
static_cast<float>(t.transform.rotation.w)),
66+
btVector3(
67+
static_cast<float>(t.transform.translation.x),
68+
static_cast<float>(t.transform.translation.y),
69+
static_cast<float>(t.transform.translation.z)));
70+
}
71+
72+
73+
/** \brief Apply a geometry_msgs TransformStamped to a Bullet-specific Vector3 type.
74+
* This function is a specialization of the doTransform template defined in tf2/convert.h
75+
* \param t_in The vector to transform, as a timestamped Bullet btVector3 data type.
76+
* \param t_out The transformed vector, as a timestamped Bullet btVector3 data type.
77+
* \param transform The timestamped transform to apply, as a TransformStamped message.
78+
*/
79+
template< >
80+
inline
81+
void doTransform(
82+
const tf2::Stamped<btVector3> & t_in, tf2::Stamped<btVector3> & t_out,
83+
const geometry_msgs::msg::TransformStamped & transform)
84+
{
85+
t_out =
86+
tf2::Stamped<btVector3>(
87+
transformToBullet(transform) * t_in,
88+
tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
89+
}
90+
91+
/** \brief Convert a stamped Bullet Vector3 type to a PointStamped message.
92+
* This function is a specialization of the toMsg template defined in tf2/convert.h
93+
* \param in The timestamped Bullet btVector3 to convert.
94+
* \return The vector converted to a PointStamped message.
95+
*/
96+
inline
97+
geometry_msgs::msg::PointStamped toMsg(const tf2::Stamped<btVector3> & in)
98+
{
99+
geometry_msgs::msg::PointStamped msg;
100+
msg.header.stamp = tf2_ros::toMsg(in.stamp_);
101+
msg.header.frame_id = in.frame_id_;
102+
msg.point.x = in[0];
103+
msg.point.y = in[1];
104+
msg.point.z = in[2];
105+
return msg;
106+
}
107+
108+
/** \brief Convert a PointStamped message type to a stamped Bullet-specific Vector3 type.
109+
* This function is a specialization of the fromMsg template defined in tf2/convert.h
110+
* \param msg The PointStamped message to convert.
111+
* \param out The point converted to a timestamped Bullet Vector3.
112+
*/
113+
inline
114+
void fromMsg(const geometry_msgs::msg::PointStamped & msg, tf2::Stamped<btVector3> & out)
115+
{
116+
out.stamp_ = tf2_ros::fromMsg(msg.header.stamp);
117+
out.frame_id_ = msg.header.frame_id;
118+
out[0] = static_cast<float>(msg.point.x);
119+
out[1] = static_cast<float>(msg.point.y);
120+
out[2] = static_cast<float>(msg.point.z);
121+
}
122+
123+
124+
/** \brief Apply a geometry_msgs TransformStamped to a Bullet-specific Transform data type.
125+
* This function is a specialization of the doTransform template defined in tf2/convert.h
126+
* \param t_in The frame to transform, as a timestamped Bullet btTransform.
127+
* \param t_out The transformed frame, as a timestamped Bullet btTransform.
128+
* \param transform The timestamped transform to apply, as a TransformStamped message.
129+
*/
130+
template< >
131+
inline
132+
void doTransform(
133+
const tf2::Stamped<btTransform> & t_in, tf2::Stamped<btTransform> & t_out,
134+
const geometry_msgs::msg::TransformStamped & transform)
135+
{
136+
t_out =
137+
tf2::Stamped<btTransform>(
138+
transformToBullet(transform) * t_in,
139+
tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
140+
}
141+
142+
143+
} // namespace tf2
144+
145+
#endif // TF2_BULLET__TF2_BULLET_HPP_

tf2_bullet/include/tf2_bullet/tf2_bullet/tf2_bullet.h

Lines changed: 0 additions & 36 deletions
This file was deleted.

tf2_bullet/mainpage.dox

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,9 +11,9 @@ by the Bullet physics engine API (see http://bulletphysics.org).
1111
See the <A HREF="http://wiki.ros.org/tf2/Tutorials/Migration/DataConversions">Conversions overview</A>
1212
wiki page for more information about datatype conversion in tf2.
1313

14-
\section codeapi Code API
14+
\section codeapi Code API
1515

16-
This library consists of one header only, tf2_bullet/tf2_bullet.h, which consists mostly of
16+
This library consists of one header only, tf2_bullet/tf2_bullet.hpp, which consists mostly of
1717
specializations of template functions defined in tf2/convert.h.
1818

1919
*/

tf2_bullet/test/test_tf2_bullet.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929
/** \author Wim Meeussen */
3030

3131

32-
#include <tf2_bullet/tf2_bullet.h>
32+
#include <tf2_bullet/tf2_bullet.hpp>
3333
#include <rclcpp/rclcpp.hpp>
3434
#include <gtest/gtest.h>
3535
#include <tf2/convert.h>

0 commit comments

Comments
 (0)