00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef pcl_ros_IMPL_TRANSFORMS_H_
00038 #define pcl_ros_IMPL_TRANSFORMS_H_
00039
00040 #include "pcl_ros/transforms.h"
00041
00042 namespace pcl_ros
00043 {
00045 template <typename PointT> void
00046 transformPointCloudWithNormals (const pcl::PointCloud <PointT> &cloud_in,
00047 pcl::PointCloud <PointT> &cloud_out, const tf::Transform &transform)
00048 {
00049
00050
00051
00052
00053
00054 tf::Quaternion q = transform.getRotation ();
00055 Eigen::Quaternionf rotation (q.w (), q.x (), q.y (), q.z ());
00056 tf::Vector3 v = transform.getOrigin ();
00057 Eigen::Vector3f origin (v.x (), v.y (), v.z ());
00058
00059
00060
00061
00062 transformPointCloudWithNormals (cloud_in, cloud_out, origin, rotation);
00063 }
00064
00066 template <typename PointT> void
00067 transformPointCloud (const pcl::PointCloud <PointT> &cloud_in,
00068 pcl::PointCloud <PointT> &cloud_out, const tf::Transform &transform)
00069 {
00070
00071
00072
00073
00074
00075 tf::Quaternion q = transform.getRotation ();
00076 Eigen::Quaternionf rotation (q.w (), q.x (), q.y (), q.z ());
00077 tf::Vector3 v = transform.getOrigin ();
00078 Eigen::Vector3f origin (v.x (), v.y (), v.z ());
00079
00080
00081
00082
00083 transformPointCloud (cloud_in, cloud_out, origin, rotation);
00084 }
00085
00087 template <typename PointT> bool
00088 transformPointCloudWithNormals (const std::string &target_frame,
00089 const pcl::PointCloud <PointT> &cloud_in,
00090 pcl::PointCloud <PointT> &cloud_out,
00091 const tf::TransformListener &tf_listener)
00092 {
00093 if (cloud_in.header.frame_id == target_frame)
00094 {
00095 cloud_out = cloud_in;
00096 return (true);
00097 }
00098
00099 tf::StampedTransform transform;
00100 try
00101 {
00102 tf_listener.lookupTransform (target_frame, cloud_in.header.frame_id, cloud_in.header.stamp, transform);
00103 }
00104 catch (tf::LookupException &e)
00105 {
00106 ROS_ERROR ("%s", e.what ());
00107 return (false);
00108 }
00109 catch (tf::ExtrapolationException &e)
00110 {
00111 ROS_ERROR ("%s", e.what ());
00112 return (false);
00113 }
00114
00115 transformPointCloudWithNormals (cloud_in, cloud_out, transform);
00116 cloud_out.header.frame_id = target_frame;
00117 return (true);
00118 }
00119
00121 template <typename PointT> bool
00122 transformPointCloud (const std::string &target_frame,
00123 const pcl::PointCloud <PointT> &cloud_in,
00124 pcl::PointCloud <PointT> &cloud_out,
00125 const tf::TransformListener &tf_listener)
00126 {
00127 if (cloud_in.header.frame_id == target_frame)
00128 {
00129 cloud_out = cloud_in;
00130 return (true);
00131 }
00132
00133 tf::StampedTransform transform;
00134 try
00135 {
00136 tf_listener.lookupTransform (target_frame, cloud_in.header.frame_id, cloud_in.header.stamp, transform);
00137 }
00138 catch (tf::LookupException &e)
00139 {
00140 ROS_ERROR ("%s", e.what ());
00141 return (false);
00142 }
00143 catch (tf::ExtrapolationException &e)
00144 {
00145 ROS_ERROR ("%s", e.what ());
00146 return (false);
00147 }
00148 transformPointCloud (cloud_in, cloud_out, transform);
00149 cloud_out.header.frame_id = target_frame;
00150 return (true);
00151 }
00152
00154 template <typename PointT> bool
00155 transformPointCloud (const std::string &target_frame,
00156 const ros::Time & target_time,
00157 const pcl::PointCloud <PointT> &cloud_in,
00158 const std::string &fixed_frame,
00159 pcl::PointCloud <PointT> &cloud_out,
00160 const tf::TransformListener &tf_listener)
00161 {
00162 tf::StampedTransform transform;
00163 try
00164 {
00165 tf_listener.lookupTransform (target_frame, target_time, cloud_in.header.frame_id, cloud_in.header.stamp, fixed_frame, transform);
00166 }
00167 catch (tf::LookupException &e)
00168 {
00169 ROS_ERROR ("%s", e.what ());
00170 return (false);
00171 }
00172 catch (tf::ExtrapolationException &e)
00173 {
00174 ROS_ERROR ("%s", e.what ());
00175 return (false);
00176 }
00177
00178 transformPointCloud (cloud_in, cloud_out, transform);
00179 cloud_out.header.frame_id = target_frame;
00180 cloud_out.header.stamp = target_time;
00181 return (true);
00182 }
00183
00185 template <typename PointT> bool
00186 transformPointCloudWithNormals (const std::string &target_frame,
00187 const ros::Time & target_time,
00188 const pcl::PointCloud <PointT> &cloud_in,
00189 const std::string &fixed_frame,
00190 pcl::PointCloud <PointT> &cloud_out,
00191 const tf::TransformListener &tf_listener)
00192 {
00193 tf::StampedTransform transform;
00194 try
00195 {
00196 tf_listener.lookupTransform (target_frame, target_time, cloud_in.header.frame_id, cloud_in.header.stamp, fixed_frame, transform);
00197 }
00198 catch (tf::LookupException &e)
00199 {
00200 ROS_ERROR ("%s", e.what ());
00201 return (false);
00202 }
00203 catch (tf::ExtrapolationException &e)
00204 {
00205 ROS_ERROR ("%s", e.what ());
00206 return (false);
00207 }
00208
00209 transformPointCloudWithNormals (cloud_in, cloud_out, transform);
00210 cloud_out.header.frame_id = target_frame;
00211 cloud_out.header.stamp = target_time;
00212 return (true);
00213 }
00214
00215 }
00216 #endif