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
00038 template <typename PointT> void
00039 pcl::demeanPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00040 const Eigen::Vector4f ¢roid,
00041 pcl::PointCloud<PointT> &cloud_out)
00042 {
00043 cloud_out = cloud_in;
00044
00045
00046 for (size_t i = 0; i < cloud_in.points.size (); ++i)
00047 cloud_out.points[i].getVector4fMap () -= centroid;
00048 }
00049
00051 template <typename PointT> void
00052 pcl::demeanPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00053 const std::vector<int> &indices,
00054 const Eigen::Vector4f ¢roid,
00055 pcl::PointCloud<PointT> &cloud_out)
00056 {
00057 cloud_out.header = cloud_in.header;
00058 cloud_out.is_dense = cloud_in.is_dense;
00059 if (indices.size () == cloud_in.points.size ())
00060 {
00061 cloud_out.width = cloud_in.width;
00062 cloud_out.height = cloud_in.height;
00063 }
00064 else
00065 {
00066 cloud_out.width = indices.size ();
00067 cloud_out.height = 1;
00068 }
00069 cloud_out.points.resize (indices.size ());
00070
00071
00072 for (size_t i = 0; i < indices.size (); ++i)
00073 cloud_out.points[i].getVector4fMap () = cloud_in.points[indices[i]].getVector4fMap () -
00074 centroid;
00075 }
00076
00078 template <typename PointT> void
00079 pcl::demeanPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00080 const Eigen::Vector4f ¢roid,
00081 Eigen::MatrixXf &cloud_out)
00082 {
00083 size_t npts = cloud_in.points.size ();
00084
00085 cloud_out = Eigen::MatrixXf::Zero (4, npts);
00086
00087 for (size_t i = 0; i < npts; ++i)
00088
00089 cloud_out.block<4, 1> (0, i) = cloud_in.points[i].getVector4fMap () - centroid;
00090
00091
00092 cloud_out.block (3, 0, 1, npts).setZero ();
00093 }
00094
00096 template <typename PointT> void
00097 pcl::demeanPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00098 const std::vector<int> &indices,
00099 const Eigen::Vector4f ¢roid,
00100 Eigen::MatrixXf &cloud_out)
00101 {
00102 size_t npts = indices.size ();
00103
00104 cloud_out = Eigen::MatrixXf::Zero (4, npts);
00105
00106 for (size_t i = 0; i < npts; ++i)
00107
00108 cloud_out.block<4, 1> (0, i) = cloud_in.points[indices[i]].getVector4fMap () - centroid;
00109
00110
00111 cloud_out.block (3, 0, 1, npts).setZero ();
00112 }
00113
00115 template <typename PointT> void
00116 pcl::transformPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00117 pcl::PointCloud<PointT> &cloud_out,
00118 const Eigen::Affine3f &transform)
00119 {
00120
00121 cloud_out.is_dense = true;
00122 if (&cloud_in != &cloud_out)
00123 {
00124
00125 cloud_out.header = cloud_in.header;
00126 cloud_out.width = cloud_in.width;
00127 cloud_out.height = cloud_in.height;
00128 cloud_out.points.reserve (cloud_out.points.size ());
00129 cloud_out.points.assign (cloud_in.points.begin (), cloud_in.points.end ());
00130 }
00131
00132 if (cloud_in.is_dense)
00133 {
00134
00135 for (size_t i = 0; i < cloud_out.points.size (); ++i)
00136 cloud_out.points[i].getVector3fMap () = transform *
00137 cloud_in.points[i].getVector3fMap ();
00138 }
00139 else
00140 {
00141
00142
00143 for (size_t i = 0; i < cloud_out.points.size (); ++i)
00144 {
00145 if (!pcl_isfinite (cloud_in.points[i].x) ||
00146 !pcl_isfinite (cloud_in.points[i].y) ||
00147 !pcl_isfinite (cloud_in.points[i].z))
00148 continue;
00149 cloud_out.points[i].getVector3fMap () = transform *
00150 cloud_in.points[i].getVector3fMap ();
00151 }
00152 }
00153 }
00154
00156 template <typename PointT> void
00157 pcl::transformPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00158 const std::vector<int> &indices,
00159 pcl::PointCloud<PointT> &cloud_out,
00160 const Eigen::Affine3f &transform)
00161 {
00162 size_t npts = indices.size ();
00163
00164 cloud_out.is_dense = true;
00165 cloud_out.header = cloud_in.header;
00166 cloud_out.width = npts;
00167 cloud_out.height = 1;
00168 cloud_out.points.resize (npts);
00169
00170 if (cloud_in.is_dense)
00171 {
00172
00173 for (size_t i = 0; i < npts; ++i)
00174 cloud_out.points[i].getVector3fMap () = transform *
00175 cloud_in.points[indices[i]].getVector3fMap ();
00176 }
00177 else
00178 {
00179
00180
00181 for (size_t i = 0; i < npts; ++i)
00182 {
00183 if (!pcl_isfinite (cloud_in.points[indices[i]].x) ||
00184 !pcl_isfinite (cloud_in.points[indices[i]].y) ||
00185 !pcl_isfinite (cloud_in.points[indices[i]].z))
00186 continue;
00187 cloud_out.points[i].getVector3fMap () = transform *
00188 cloud_in.points[indices[i]].getVector3fMap ();
00189 }
00190 }
00191 }
00192
00194 template <typename PointT> void
00195 pcl::transformPointCloudWithNormals (const pcl::PointCloud<PointT> &cloud_in,
00196 pcl::PointCloud<PointT> &cloud_out,
00197 const Eigen::Affine3f &transform)
00198 {
00199 if (&cloud_in != &cloud_out)
00200 {
00201
00202 cloud_out.header = cloud_in.header;
00203 cloud_out.width = cloud_in.width;
00204 cloud_out.height = cloud_in.height;
00205 cloud_out.is_dense = cloud_in.is_dense;
00206 cloud_out.points.reserve (cloud_out.points.size ());
00207 cloud_out.points.assign (cloud_in.points.begin (), cloud_in.points.end ());
00208 }
00209
00210
00211 if (cloud_in.is_dense)
00212 {
00213 for (size_t i = 0; i < cloud_out.points.size (); ++i)
00214 {
00215 cloud_out.points[i].getVector3fMap() = transform *
00216 cloud_in.points[i].getVector3fMap ();
00217
00218
00219 cloud_out.points[i].getNormalVector3fMap() = transform.rotation () *
00220 cloud_in.points[i].getNormalVector3fMap ();
00221 }
00222 }
00223
00224 else
00225 {
00226 for (size_t i = 0; i < cloud_out.points.size (); ++i)
00227 {
00228 if (!pcl_isfinite (cloud_in.points[i].x) ||
00229 !pcl_isfinite (cloud_in.points[i].y) ||
00230 !pcl_isfinite (cloud_in.points[i].z))
00231 continue;
00232 cloud_out.points[i].getVector3fMap() = transform *
00233 cloud_in.points[i].getVector3fMap ();
00234
00235
00236 cloud_out.points[i].getNormalVector3fMap() = transform.rotation () *
00237 cloud_in.points[i].getNormalVector3fMap ();
00238 }
00239 }
00240 }
00241
00243 template <typename PointT> void
00244 pcl::transformPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00245 pcl::PointCloud<PointT> &cloud_out,
00246 const Eigen::Matrix4f &transform)
00247 {
00248 if (&cloud_in != &cloud_out)
00249 {
00250
00251 cloud_out.header = cloud_in.header;
00252 cloud_out.width = cloud_in.width;
00253 cloud_out.height = cloud_in.height;
00254 cloud_out.is_dense = cloud_in.is_dense;
00255 cloud_out.points.reserve (cloud_out.points.size ());
00256 cloud_out.points.assign (cloud_in.points.begin (), cloud_in.points.end ());
00257 }
00258
00259 Eigen::Matrix3f rot = transform.block<3, 3> (0, 0);
00260 Eigen::Vector3f trans = transform.block<3, 1> (0, 3);
00261
00262 if (cloud_in.is_dense)
00263 {
00264 for (size_t i = 0; i < cloud_out.points.size (); ++i)
00265 cloud_out.points[i].getVector3fMap () = rot *
00266 cloud_in.points[i].getVector3fMap () + trans;
00267 }
00268
00269 else
00270 {
00271 for (size_t i = 0; i < cloud_out.points.size (); ++i)
00272 {
00273 if (!pcl_isfinite (cloud_in.points[i].x) ||
00274 !pcl_isfinite (cloud_in.points[i].y) ||
00275 !pcl_isfinite (cloud_in.points[i].z))
00276 continue;
00277 cloud_out.points[i].getVector3fMap () = rot *
00278 cloud_in.points[i].getVector3fMap () + trans;
00279 }
00280 }
00281 }
00282
00284 template <typename PointT> void
00285 pcl::transformPointCloudWithNormals (const pcl::PointCloud<PointT> &cloud_in,
00286 pcl::PointCloud<PointT> &cloud_out,
00287 const Eigen::Matrix4f &transform)
00288 {
00289 if (&cloud_in != &cloud_out)
00290 {
00291
00292 cloud_out.header = cloud_in.header;
00293 cloud_out.width = cloud_in.width;
00294 cloud_out.height = cloud_in.height;
00295 cloud_out.is_dense = cloud_in.is_dense;
00296 cloud_out.points.reserve (cloud_out.points.size ());
00297 cloud_out.points.assign (cloud_in.points.begin (), cloud_in.points.end ());
00298 }
00299
00300 Eigen::Matrix3f rot = transform.block<3, 3> (0, 0);
00301 Eigen::Vector3f trans = transform.block<3, 1> (0, 3);
00302
00303
00304 if (cloud_in.is_dense)
00305 {
00306 for (size_t i = 0; i < cloud_out.points.size (); ++i)
00307 {
00308 cloud_out.points[i].getVector3fMap () = rot *
00309 cloud_in.points[i].getVector3fMap () + trans;
00310
00311
00312 cloud_out.points[i].getNormalVector3fMap() = rot *
00313 cloud_in.points[i].getNormalVector3fMap ();
00314 }
00315 }
00316
00317 else
00318 {
00319 for (size_t i = 0; i < cloud_out.points.size (); ++i)
00320 {
00321 if (!pcl_isfinite (cloud_in.points[i].x) ||
00322 !pcl_isfinite (cloud_in.points[i].y) ||
00323 !pcl_isfinite (cloud_in.points[i].z))
00324 continue;
00325 cloud_out.points[i].getVector3fMap () = rot *
00326 cloud_in.points[i].getVector3fMap () + trans;
00327
00328
00329 cloud_out.points[i].getNormalVector3fMap() = rot *
00330 cloud_in.points[i].getNormalVector3fMap ();
00331 }
00332 }
00333 }
00334
00336 template <typename PointT> inline void
00337 pcl::transformPointCloud (const pcl::PointCloud<PointT> &cloud_in,
00338 pcl::PointCloud<PointT> &cloud_out,
00339 const Eigen::Vector3f &offset,
00340 const Eigen::Quaternionf &rotation)
00341 {
00342 Eigen::Translation3f translation (offset);
00343
00344 Eigen::Affine3f t;
00345 t = translation * rotation;
00346 transformPointCloud (cloud_in, cloud_out, t);
00347 }
00348
00350 template <typename PointT> inline void
00351 pcl::transformPointCloudWithNormals (const pcl::PointCloud<PointT> &cloud_in,
00352 pcl::PointCloud<PointT> &cloud_out,
00353 const Eigen::Vector3f &offset,
00354 const Eigen::Quaternionf &rotation)
00355 {
00356 Eigen::Translation3f translation (offset);
00357
00358 Eigen::Affine3f t;
00359 t = translation * rotation;
00360 transformPointCloudWithNormals (cloud_in, cloud_out, t);
00361 }