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 
45 namespace pcl_ros
46 {
53  template <typename PointT> void
54  transformPointCloudWithNormals (const pcl::PointCloud <PointT> &cloud_in,
55  pcl::PointCloud <PointT> &cloud_out,
56  const tf::Transform &transform);
57 
64  template <typename PointT> bool
65  transformPointCloudWithNormals (const std::string &target_frame,
66  const pcl::PointCloud <PointT> &cloud_in,
67  pcl::PointCloud <PointT> &cloud_out,
68  const tf::TransformListener &tf_listener);
69 
78  template <typename PointT> bool
79  transformPointCloudWithNormals (const std::string &target_frame,
80  const ros::Time & target_time,
81  const pcl::PointCloud <PointT> &cloud_in,
82  const std::string &fixed_frame,
83  pcl::PointCloud <PointT> &cloud_out,
84  const tf::TransformListener &tf_listener);
85 
92  template <typename PointT> void
93  transformPointCloud (const pcl::PointCloud <PointT> &cloud_in,
94  pcl::PointCloud <PointT> &cloud_out,
95  const tf::Transform &transform);
96 
103  template <typename PointT> bool
104  transformPointCloud (const std::string &target_frame,
105  const pcl::PointCloud <PointT> &cloud_in,
106  pcl::PointCloud <PointT> &cloud_out,
107  const tf::TransformListener &tf_listener);
108 
117  template <typename PointT> bool
118  transformPointCloud (const std::string &target_frame, const ros::Time & target_time,
119  const pcl::PointCloud <PointT> &cloud_in,
120  const std::string &fixed_frame,
121  pcl::PointCloud <PointT> &cloud_out,
122  const tf::TransformListener &tf_listener);
123 
130  bool
131  transformPointCloud (const std::string &target_frame,
132  const sensor_msgs::PointCloud2 &in,
133  sensor_msgs::PointCloud2 &out,
134  const tf::TransformListener &tf_listener);
135 
142  void
143  transformPointCloud (const std::string &target_frame,
144  const tf::Transform &net_transform,
145  const sensor_msgs::PointCloud2 &in,
146  sensor_msgs::PointCloud2 &out);
147 
153  void
154  transformPointCloud (const Eigen::Matrix4f &transform,
155  const sensor_msgs::PointCloud2 &in,
156  sensor_msgs::PointCloud2 &out);
157 
162  void
163  transformAsMatrix (const tf::Transform& bt, Eigen::Matrix4f &out_mat);
164 }
165 
166 #endif // PCL_ROS_TRANSFORMS_H_
167 
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 transformAsMatrix(const tf::Transform &bt, Eigen::Matrix4f &out_mat)
Obtain the transformation matrix from TF into an Eigen form.
Definition: transforms.cpp:212
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


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