transforms.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *
00035  */
00036 
00037 #ifndef pcl_ROS_TRANSFORMS_H_
00038 #define pcl_ROS_TRANSFORMS_H_
00039 
00040 #include <sensor_msgs/PointCloud2.h>
00041 #include <pcl/common/transforms.h>
00042 #include <tf/transform_datatypes.h>
00043 #include <tf/transform_listener.h>
00044 
00045 namespace pcl_ros
00046 {
00053   template <typename PointT> void 
00054   transformPointCloudWithNormals (const pcl::PointCloud <PointT> &cloud_in, 
00055                                   pcl::PointCloud <PointT> &cloud_out, 
00056                                   const tf::Transform &transform);
00057 
00064   template <typename PointT> bool 
00065   transformPointCloudWithNormals (const std::string &target_frame, 
00066                                   const pcl::PointCloud <PointT> &cloud_in, 
00067                                   pcl::PointCloud <PointT> &cloud_out, 
00068                                   const tf::TransformListener &tf_listener);
00069 
00078    template <typename PointT> bool 
00079    transformPointCloudWithNormals (const std::string &target_frame, 
00080                                    const ros::Time & target_time, 
00081                                    const pcl::PointCloud <PointT> &cloud_in, 
00082                                    const std::string &fixed_frame, 
00083                                    pcl::PointCloud <PointT> &cloud_out, 
00084                                    const tf::TransformListener &tf_listener);
00085 
00092   template <typename PointT> void 
00093   transformPointCloud (const pcl::PointCloud <PointT> &cloud_in, 
00094                        pcl::PointCloud <PointT> &cloud_out, 
00095                        const tf::Transform &transform);
00096 
00103   template <typename PointT> bool 
00104   transformPointCloud (const std::string &target_frame, 
00105                        const pcl::PointCloud <PointT> &cloud_in, 
00106                        pcl::PointCloud <PointT> &cloud_out, 
00107                        const tf::TransformListener &tf_listener);
00108 
00117   template <typename PointT> bool 
00118   transformPointCloud (const std::string &target_frame, const ros::Time & target_time, 
00119                        const pcl::PointCloud <PointT> &cloud_in, 
00120                        const std::string &fixed_frame, 
00121                        pcl::PointCloud <PointT> &cloud_out, 
00122                        const tf::TransformListener &tf_listener);
00123 
00130   bool 
00131   transformPointCloud (const std::string &target_frame, 
00132                        const sensor_msgs::PointCloud2 &in, 
00133                        sensor_msgs::PointCloud2 &out, 
00134                        const tf::TransformListener &tf_listener);
00135 
00142   void 
00143   transformPointCloud (const std::string &target_frame, 
00144                        const tf::Transform &net_transform, 
00145                        const sensor_msgs::PointCloud2 &in, 
00146                        sensor_msgs::PointCloud2 &out);
00147 
00153   void 
00154   transformPointCloud (const Eigen::Matrix4f &transform, 
00155                        const sensor_msgs::PointCloud2 &in, 
00156                        sensor_msgs::PointCloud2 &out);
00157 
00162   void 
00163   transformAsMatrix (const tf::Transform& bt, Eigen::Matrix4f &out_mat);
00164 }
00165 
00166 #endif // PCL_ROS_TRANSFORMS_H_
00167 


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu May 5 2016 04:16:43