Skip to content

Commit ee73829

Browse files
authored
Deprecate tf2_sensor_msgs.h (#416)
Switch to tf2_sensor_msgs.hpp instead. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 01da538 commit ee73829

File tree

3 files changed

+102
-65
lines changed

3 files changed

+102
-65
lines changed

tf2_sensor_msgs/include/tf2_sensor_msgs/tf2_sensor_msgs.h

Lines changed: 2 additions & 64 deletions
Original file line numberDiff line numberDiff line change
@@ -30,70 +30,8 @@
3030
#ifndef TF2_SENSOR_MSGS_H
3131
#define TF2_SENSOR_MSGS_H
3232

33-
#include <tf2/convert.h>
34-
#include <tf2/time.h>
35-
#include <sensor_msgs/msg/point_cloud2.hpp>
36-
#include <sensor_msgs/point_cloud2_iterator.hpp>
37-
#include <Eigen/Eigen>
38-
#include <Eigen/Geometry>
39-
#include <tf2_ros/buffer_interface.h>
33+
#warning This header is obsolete, please include tf2_sensor_msgs/tf2_sensor_msgs.hpp instead
4034

41-
namespace tf2
42-
{
43-
44-
/********************/
45-
/** PointCloud2 **/
46-
/********************/
47-
48-
// method to extract timestamp from object
49-
template <>
50-
inline
51-
tf2::TimePoint getTimestamp(const sensor_msgs::msg::PointCloud2& p) {return tf2_ros::fromMsg(p.header.stamp);}
52-
53-
// method to extract frame id from object
54-
template <>
55-
inline
56-
std::string getFrameId(const sensor_msgs::msg::PointCloud2 &p) {return p.header.frame_id;}
57-
58-
// this method needs to be implemented by client library developers
59-
template <>
60-
inline
61-
void doTransform(const sensor_msgs::msg::PointCloud2 &p_in, sensor_msgs::msg::PointCloud2 &p_out, const geometry_msgs::msg::TransformStamped& t_in)
62-
{
63-
p_out = p_in;
64-
p_out.header = t_in.header;
65-
Eigen::Transform<float,3,Eigen::Affine> t = Eigen::Translation3f(t_in.transform.translation.x, t_in.transform.translation.y,
66-
t_in.transform.translation.z) * Eigen::Quaternion<float>(
67-
t_in.transform.rotation.w, t_in.transform.rotation.x,
68-
t_in.transform.rotation.y, t_in.transform.rotation.z);
69-
70-
sensor_msgs::PointCloud2ConstIterator<float> x_in(p_in, std::string("x"));
71-
sensor_msgs::PointCloud2ConstIterator<float> y_in(p_in, std::string("y"));
72-
sensor_msgs::PointCloud2ConstIterator<float> z_in(p_in, std::string("z"));
73-
74-
sensor_msgs::PointCloud2Iterator<float> x_out(p_out, std::string("x"));
75-
sensor_msgs::PointCloud2Iterator<float> y_out(p_out, std::string("y"));
76-
sensor_msgs::PointCloud2Iterator<float> z_out(p_out, std::string("z"));
77-
78-
Eigen::Vector3f point;
79-
for(; x_in != x_in.end(); ++x_in, ++y_in, ++z_in, ++x_out, ++y_out, ++z_out) {
80-
point = t * Eigen::Vector3f(*x_in, *y_in, *z_in);
81-
*x_out = point.x();
82-
*y_out = point.y();
83-
*z_out = point.z();
84-
}
85-
}
86-
inline
87-
sensor_msgs::msg::PointCloud2 toMsg(const sensor_msgs::msg::PointCloud2 &in)
88-
{
89-
return in;
90-
}
91-
inline
92-
void fromMsg(const sensor_msgs::msg::PointCloud2 &msg, sensor_msgs::msg::PointCloud2 &out)
93-
{
94-
out = msg;
95-
}
96-
97-
} // namespace
35+
#include <tf2_sensor_msgs/tf2_sensor_msgs.hpp>
9836

9937
#endif // TF2_SENSOR_MSGS_H
Lines changed: 99 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,99 @@
1+
/*
2+
* Copyright (c) 2008, Willow Garage, Inc.
3+
* All rights reserved.
4+
*
5+
* Redistribution and use in source and binary forms, with or without
6+
* modification, are permitted provided that the following conditions are met:
7+
*
8+
* * Redistributions of source code must retain the above copyright
9+
* notice, this list of conditions and the following disclaimer.
10+
* * Redistributions in binary form must reproduce the above copyright
11+
* notice, this list of conditions and the following disclaimer in the
12+
* documentation and/or other materials provided with the distribution.
13+
* * Neither the name of the Willow 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 OWNER 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+
30+
#ifndef TF2_SENSOR_MSGS_HPP
31+
#define TF2_SENSOR_MSGS_HPP
32+
33+
#include <tf2/convert.h>
34+
#include <tf2/time.h>
35+
#include <sensor_msgs/msg/point_cloud2.hpp>
36+
#include <sensor_msgs/point_cloud2_iterator.hpp>
37+
#include <Eigen/Eigen>
38+
#include <Eigen/Geometry>
39+
#include <tf2_ros/buffer_interface.h>
40+
41+
namespace tf2
42+
{
43+
44+
/********************/
45+
/** PointCloud2 **/
46+
/********************/
47+
48+
// method to extract timestamp from object
49+
template <>
50+
inline
51+
tf2::TimePoint getTimestamp(const sensor_msgs::msg::PointCloud2& p) {return tf2_ros::fromMsg(p.header.stamp);}
52+
53+
// method to extract frame id from object
54+
template <>
55+
inline
56+
std::string getFrameId(const sensor_msgs::msg::PointCloud2 &p) {return p.header.frame_id;}
57+
58+
// this method needs to be implemented by client library developers
59+
template <>
60+
inline
61+
void doTransform(const sensor_msgs::msg::PointCloud2 &p_in, sensor_msgs::msg::PointCloud2 &p_out, const geometry_msgs::msg::TransformStamped& t_in)
62+
{
63+
p_out = p_in;
64+
p_out.header = t_in.header;
65+
Eigen::Transform<float,3,Eigen::Affine> t = Eigen::Translation3f(t_in.transform.translation.x, t_in.transform.translation.y,
66+
t_in.transform.translation.z) * Eigen::Quaternion<float>(
67+
t_in.transform.rotation.w, t_in.transform.rotation.x,
68+
t_in.transform.rotation.y, t_in.transform.rotation.z);
69+
70+
sensor_msgs::PointCloud2ConstIterator<float> x_in(p_in, std::string("x"));
71+
sensor_msgs::PointCloud2ConstIterator<float> y_in(p_in, std::string("y"));
72+
sensor_msgs::PointCloud2ConstIterator<float> z_in(p_in, std::string("z"));
73+
74+
sensor_msgs::PointCloud2Iterator<float> x_out(p_out, std::string("x"));
75+
sensor_msgs::PointCloud2Iterator<float> y_out(p_out, std::string("y"));
76+
sensor_msgs::PointCloud2Iterator<float> z_out(p_out, std::string("z"));
77+
78+
Eigen::Vector3f point;
79+
for(; x_in != x_in.end(); ++x_in, ++y_in, ++z_in, ++x_out, ++y_out, ++z_out) {
80+
point = t * Eigen::Vector3f(*x_in, *y_in, *z_in);
81+
*x_out = point.x();
82+
*y_out = point.y();
83+
*z_out = point.z();
84+
}
85+
}
86+
inline
87+
sensor_msgs::msg::PointCloud2 toMsg(const sensor_msgs::msg::PointCloud2 &in)
88+
{
89+
return in;
90+
}
91+
inline
92+
void fromMsg(const sensor_msgs::msg::PointCloud2 &msg, sensor_msgs::msg::PointCloud2 &out)
93+
{
94+
out = msg;
95+
}
96+
97+
} // namespace
98+
99+
#endif // TF2_SENSOR_MSGS_HPP

tf2_sensor_msgs/test/test_tf2_sensor_msgs.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@
2828
*/
2929

3030

31-
#include <tf2_sensor_msgs/tf2_sensor_msgs.h>
31+
#include <tf2_sensor_msgs/tf2_sensor_msgs.hpp>
3232
#include <geometry_msgs/PoseStamped.h>
3333
#include <tf2_ros/transform_listener.h>
3434
#include <ros/ros.h>

0 commit comments

Comments
 (0)