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 #include "rtabmap/core/util3d_transforms.h"
00029
00030 #include <pcl/common/transforms.h>
00031
00032 namespace rtabmap
00033 {
00034
00035 namespace util3d
00036 {
00037
00038 pcl::PointCloud<pcl::PointXYZ>::Ptr transformPointCloud(
00039 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00040 const Transform & transform)
00041 {
00042 pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
00043 pcl::transformPointCloud(*cloud, *output, transform.toEigen4f());
00044 return output;
00045 }
00046 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformPointCloud(
00047 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00048 const Transform & transform)
00049 {
00050 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGB>);
00051 pcl::transformPointCloud(*cloud, *output, transform.toEigen4f());
00052 return output;
00053 }
00054 pcl::PointCloud<pcl::PointNormal>::Ptr transformPointCloud(
00055 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00056 const Transform & transform)
00057 {
00058 pcl::PointCloud<pcl::PointNormal>::Ptr output(new pcl::PointCloud<pcl::PointNormal>);
00059 pcl::transformPointCloudWithNormals(*cloud, *output, transform.toEigen4f());
00060 return output;
00061 }
00062 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformPointCloud(
00063 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00064 const Transform & transform)
00065 {
00066 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00067 pcl::transformPointCloudWithNormals(*cloud, *output, transform.toEigen4f());
00068 return output;
00069 }
00070
00071 cv::Point3f transformPoint(
00072 const cv::Point3f & point,
00073 const Transform & transform)
00074 {
00075 cv::Point3f ret = point;
00076 ret.x = transform (0, 0) * point.x + transform (0, 1) * point.y + transform (0, 2) * point.z + transform (0, 3);
00077 ret.y = transform (1, 0) * point.x + transform (1, 1) * point.y + transform (1, 2) * point.z + transform (1, 3);
00078 ret.z = transform (2, 0) * point.x + transform (2, 1) * point.y + transform (2, 2) * point.z + transform (2, 3);
00079 return ret;
00080 }
00081 pcl::PointXYZ transformPoint(
00082 const pcl::PointXYZ & pt,
00083 const Transform & transform)
00084 {
00085 return pcl::transformPoint(pt, transform.toEigen3f());
00086 }
00087 pcl::PointXYZRGB transformPoint(
00088 const pcl::PointXYZRGB & pt,
00089 const Transform & transform)
00090 {
00091 return pcl::transformPoint(pt, transform.toEigen3f());
00092 }
00093 pcl::PointNormal transformPoint(
00094 const pcl::PointNormal & point,
00095 const Transform & transform)
00096 {
00097 pcl::PointNormal ret;
00098 Eigen::Matrix<float, 3, 1> pt (point.x, point.y, point.z);
00099 ret.x = static_cast<float> (transform (0, 0) * pt.coeffRef (0) + transform (0, 1) * pt.coeffRef (1) + transform (0, 2) * pt.coeffRef (2) + transform (0, 3));
00100 ret.y = static_cast<float> (transform (1, 0) * pt.coeffRef (0) + transform (1, 1) * pt.coeffRef (1) + transform (1, 2) * pt.coeffRef (2) + transform (1, 3));
00101 ret.z = static_cast<float> (transform (2, 0) * pt.coeffRef (0) + transform (2, 1) * pt.coeffRef (1) + transform (2, 2) * pt.coeffRef (2) + transform (2, 3));
00102
00103
00104 Eigen::Matrix<float, 3, 1> nt (point.normal_x, point.normal_y, point.normal_z);
00105 ret.normal_x = static_cast<float> (transform (0, 0) * nt.coeffRef (0) + transform (0, 1) * nt.coeffRef (1) + transform (0, 2) * nt.coeffRef (2));
00106 ret.normal_y = static_cast<float> (transform (1, 0) * nt.coeffRef (0) + transform (1, 1) * nt.coeffRef (1) + transform (1, 2) * nt.coeffRef (2));
00107 ret.normal_z = static_cast<float> (transform (2, 0) * nt.coeffRef (0) + transform (2, 1) * nt.coeffRef (1) + transform (2, 2) * nt.coeffRef (2));
00108 return ret;
00109 }
00110
00111 }
00112
00113 }