transforms.h
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_TRANSFORMS_H_
38 #define pcl_ROS_TRANSFORMS_H_
39 
40 #include <sensor_msgs/PointCloud2.h>
41 #include <pcl/common/transforms.h>
42 #include <tf/transform_datatypes.h>
43 #include <tf/transform_listener.h>
44 #include <tf2_ros/buffer.h>
45 
46 namespace pcl_ros
47 {
54  template <typename PointT> void
55  transformPointCloudWithNormals (const pcl::PointCloud <PointT> &cloud_in,
56  pcl::PointCloud <PointT> &cloud_out,
57  const tf::Transform &transform);
58 
65  template <typename PointT> void
66  transformPointCloudWithNormals (const pcl::PointCloud <PointT> &cloud_in,
67  pcl::PointCloud <PointT> &cloud_out,
68  const geometry_msgs::Transform &transform);
69 
76  template <typename PointT> bool
77  transformPointCloudWithNormals (const std::string &target_frame,
78  const pcl::PointCloud <PointT> &cloud_in,
79  pcl::PointCloud <PointT> &cloud_out,
80  const tf::TransformListener &tf_listener);
81 
88  template <typename PointT> bool
89  transformPointCloudWithNormals (const std::string &target_frame,
90  const pcl::PointCloud <PointT> &cloud_in,
91  pcl::PointCloud <PointT> &cloud_out,
92  const tf2_ros::Buffer &tf_buffer);
93 
102  template <typename PointT> bool
103  transformPointCloudWithNormals (const std::string &target_frame,
104  const ros::Time & target_time,
105  const pcl::PointCloud <PointT> &cloud_in,
106  const std::string &fixed_frame,
107  pcl::PointCloud <PointT> &cloud_out,
108  const tf::TransformListener &tf_listener);
109 
118  template <typename PointT> bool
119  transformPointCloudWithNormals (const std::string &target_frame,
120  const ros::Time & target_time,
121  const pcl::PointCloud <PointT> &cloud_in,
122  const std::string &fixed_frame,
123  pcl::PointCloud <PointT> &cloud_out,
124  const tf2_ros::Buffer &tf_buffer);
125 
132  template <typename PointT> void
133  transformPointCloud (const pcl::PointCloud <PointT> &cloud_in,
134  pcl::PointCloud <PointT> &cloud_out,
135  const tf::Transform &transform);
136 
143  template <typename PointT> void
144  transformPointCloud (const pcl::PointCloud <PointT> &cloud_in,
145  pcl::PointCloud <PointT> &cloud_out,
146  const geometry_msgs::Transform &transform);
147 
154  template <typename PointT> bool
155  transformPointCloud (const std::string &target_frame,
156  const pcl::PointCloud <PointT> &cloud_in,
157  pcl::PointCloud <PointT> &cloud_out,
158  const tf::TransformListener &tf_listener);
159 
166  template <typename PointT> bool
167  transformPointCloud (const std::string &target_frame,
168  const pcl::PointCloud <PointT> &cloud_in,
169  pcl::PointCloud <PointT> &cloud_out,
170  const tf2_ros::Buffer &tf_buffer);
171 
180  template <typename PointT> bool
181  transformPointCloud (const std::string &target_frame, const ros::Time & target_time,
182  const pcl::PointCloud <PointT> &cloud_in,
183  const std::string &fixed_frame,
184  pcl::PointCloud <PointT> &cloud_out,
185  const tf::TransformListener &tf_listener);
186 
195  template <typename PointT> bool
196  transformPointCloud (const std::string &target_frame, const ros::Time & target_time,
197  const pcl::PointCloud <PointT> &cloud_in,
198  const std::string &fixed_frame,
199  pcl::PointCloud <PointT> &cloud_out,
200  const tf2_ros::Buffer &tf_buffer);
201 
208  bool
209  transformPointCloud (const std::string &target_frame,
210  const sensor_msgs::PointCloud2 &in,
211  sensor_msgs::PointCloud2 &out,
212  const tf::TransformListener &tf_listener);
213 
220  bool
221  transformPointCloud (const std::string &target_frame,
222  const sensor_msgs::PointCloud2 &in,
223  sensor_msgs::PointCloud2 &out,
224  const tf2_ros::Buffer &tf_buffer);
225 
232  void
233  transformPointCloud (const std::string &target_frame,
234  const tf::Transform &net_transform,
235  const sensor_msgs::PointCloud2 &in,
236  sensor_msgs::PointCloud2 &out);
237 
244  void
245  transformPointCloud (const std::string &target_frame,
246  const geometry_msgs::Transform &net_transform,
247  const sensor_msgs::PointCloud2 &in,
248  sensor_msgs::PointCloud2 &out);
249 
255  void
256  transformPointCloud (const Eigen::Matrix4f &transform,
257  const sensor_msgs::PointCloud2 &in,
258  sensor_msgs::PointCloud2 &out);
259 
264  void
265  transformAsMatrix (const tf::Transform& bt, Eigen::Matrix4f &out_mat);
266 
271  void
272  transformAsMatrix (const geometry_msgs::Transform& bt, Eigen::Matrix4f &out_mat);
273 }
274 
275 #endif // PCL_ROS_TRANSFORMS_H_
276 
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:51
void transformAsMatrix(const tf::Transform &bt, Eigen::Matrix4f &out_mat)
Obtain the transformation matrix from TF into an Eigen form.
Definition: transforms.cpp:259
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:85


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu Feb 16 2023 03:08:03