transforms.hpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, 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 Willow Garage, Inc. 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  */
36 
37 #ifndef pcl_ros_IMPL_TRANSFORMS_H_
38 #define pcl_ros_IMPL_TRANSFORMS_H_
39 
41 #include "pcl_ros/transforms.h"
42 
45 
46 namespace pcl_ros
47 {
49 template <typename PointT> void
50 transformPointCloudWithNormals (const pcl::PointCloud <PointT> &cloud_in,
51  pcl::PointCloud <PointT> &cloud_out, const tf::Transform &transform)
52 {
53  // Bullet (used by tf) and Eigen both store quaternions in x,y,z,w order, despite the ordering
54  // of arguments in Eigen's constructor. We could use an Eigen Map to convert without copy, but
55  // this only works if Bullet uses floats, that is if BT_USE_DOUBLE_PRECISION is not defined.
56  // Rather that risking a mistake, we copy the quaternion, which is a small cost compared to
57  // the conversion of the point cloud anyway. Idem for the origin.
58  tf::Quaternion q = transform.getRotation ();
59  Eigen::Quaternionf rotation (q.w (), q.x (), q.y (), q.z ()); // internally stored as (x,y,z,w)
60  tf::Vector3 v = transform.getOrigin ();
61  Eigen::Vector3f origin (v.x (), v.y (), v.z ());
62  // Eigen::Translation3f translation(v);
63  // Assemble an Eigen Transform
64  //Eigen::Transform3f t;
65  //t = translation * rotation;
66  transformPointCloudWithNormals (cloud_in, cloud_out, origin, rotation);
67 }
68 
70 template <typename PointT> void
71 transformPointCloud (const pcl::PointCloud <PointT> &cloud_in,
72  pcl::PointCloud <PointT> &cloud_out, const tf::Transform &transform)
73 {
74  // Bullet (used by tf) and Eigen both store quaternions in x,y,z,w order, despite the ordering
75  // of arguments in Eigen's constructor. We could use an Eigen Map to convert without copy, but
76  // this only works if Bullet uses floats, that is if BT_USE_DOUBLE_PRECISION is not defined.
77  // Rather that risking a mistake, we copy the quaternion, which is a small cost compared to
78  // the conversion of the point cloud anyway. Idem for the origin.
79  tf::Quaternion q = transform.getRotation ();
80  Eigen::Quaternionf rotation (q.w (), q.x (), q.y (), q.z ()); // internally stored as (x,y,z,w)
81  tf::Vector3 v = transform.getOrigin ();
82  Eigen::Vector3f origin (v.x (), v.y (), v.z ());
83  // Eigen::Translation3f translation(v);
84  // Assemble an Eigen Transform
85  //Eigen::Transform3f t;
86  //t = translation * rotation;
87  transformPointCloud (cloud_in, cloud_out, origin, rotation);
88 }
89 
91 template <typename PointT> bool
92 transformPointCloudWithNormals (const std::string &target_frame,
93  const pcl::PointCloud <PointT> &cloud_in,
94  pcl::PointCloud <PointT> &cloud_out,
95  const tf::TransformListener &tf_listener)
96 {
97  if (cloud_in.header.frame_id == target_frame)
98  {
99  cloud_out = cloud_in;
100  return (true);
101  }
102 
103  tf::StampedTransform transform;
104  try
105  {
106  tf_listener.lookupTransform (target_frame, cloud_in.header.frame_id, fromPCL(cloud_in.header).stamp, transform);
107  }
108  catch (tf::LookupException &e)
109  {
110  ROS_ERROR ("%s", e.what ());
111  return (false);
112  }
113  catch (tf::ExtrapolationException &e)
114  {
115  ROS_ERROR ("%s", e.what ());
116  return (false);
117  }
118 
119  transformPointCloudWithNormals (cloud_in, cloud_out, transform);
120  cloud_out.header.frame_id = target_frame;
121  return (true);
122 }
123 
125 template <typename PointT> bool
126 transformPointCloud (const std::string &target_frame,
127  const pcl::PointCloud <PointT> &cloud_in,
128  pcl::PointCloud <PointT> &cloud_out,
129  const tf::TransformListener &tf_listener)
130 {
131  if (cloud_in.header.frame_id == target_frame)
132  {
133  cloud_out = cloud_in;
134  return (true);
135  }
136 
137  tf::StampedTransform transform;
138  try
139  {
140  tf_listener.lookupTransform (target_frame, cloud_in.header.frame_id, fromPCL(cloud_in.header).stamp, transform);
141  }
142  catch (tf::LookupException &e)
143  {
144  ROS_ERROR ("%s", e.what ());
145  return (false);
146  }
147  catch (tf::ExtrapolationException &e)
148  {
149  ROS_ERROR ("%s", e.what ());
150  return (false);
151  }
152  transformPointCloud (cloud_in, cloud_out, transform);
153  cloud_out.header.frame_id = target_frame;
154  return (true);
155 }
156 
158 template <typename PointT> bool
159 transformPointCloud (const std::string &target_frame,
160  const ros::Time & target_time,
161  const pcl::PointCloud <PointT> &cloud_in,
162  const std::string &fixed_frame,
163  pcl::PointCloud <PointT> &cloud_out,
164  const tf::TransformListener &tf_listener)
165 {
166  tf::StampedTransform transform;
167  try
168  {
169  tf_listener.lookupTransform (target_frame, target_time, cloud_in.header.frame_id, fromPCL(cloud_in.header).stamp, fixed_frame, transform);
170  }
171  catch (tf::LookupException &e)
172  {
173  ROS_ERROR ("%s", e.what ());
174  return (false);
175  }
176  catch (tf::ExtrapolationException &e)
177  {
178  ROS_ERROR ("%s", e.what ());
179  return (false);
180  }
181 
182  transformPointCloud (cloud_in, cloud_out, transform);
183  cloud_out.header.frame_id = target_frame;
184  std_msgs::Header header;
185  header.stamp = target_time;
186  cloud_out.header = toPCL(header);
187  return (true);
188 }
189 
191 template <typename PointT> bool
192 transformPointCloudWithNormals (const std::string &target_frame,
193  const ros::Time & target_time,
194  const pcl::PointCloud <PointT> &cloud_in,
195  const std::string &fixed_frame,
196  pcl::PointCloud <PointT> &cloud_out,
197  const tf::TransformListener &tf_listener)
198 {
199  tf::StampedTransform transform;
200  try
201  {
202  tf_listener.lookupTransform (target_frame, target_time, cloud_in.header.frame_id, fromPCL(cloud_in.header).stamp, fixed_frame, transform);
203  }
204  catch (tf::LookupException &e)
205  {
206  ROS_ERROR ("%s", e.what ());
207  return (false);
208  }
209  catch (tf::ExtrapolationException &e)
210  {
211  ROS_ERROR ("%s", e.what ());
212  return (false);
213  }
214 
215  transformPointCloudWithNormals (cloud_in, cloud_out, transform);
216  cloud_out.header.frame_id = target_frame;
217  std_msgs::Header header;
218  header.stamp = target_time;
219  cloud_out.header = toPCL(header);
220  return (true);
221 }
222 
223 } // namespace pcl_ros
224 #endif
void transformPointCloudWithNormals(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
Transform a point cloud and rotate its normals using an Eigen transform.
Definition: transforms.hpp:50
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
Quaternion getRotation() const
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
Apply a rigid transform defined by a 3D offset and a quaternion.
Definition: transforms.hpp:71
const std::string header
#define ROS_ERROR(...)
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Jun 5 2019 19:52:52