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 #include <rtabmap/utilite/ULogger.h>
00032
00033 namespace rtabmap
00034 {
00035
00036 namespace util3d
00037 {
00038
00039 LaserScan transformLaserScan(const LaserScan & laserScan, const Transform & transform)
00040 {
00041 cv::Mat output = laserScan.data().clone();
00042
00043 if(!transform.isNull() && !transform.isIdentity())
00044 {
00045 Eigen::Affine3f transform3f = transform.toEigen3f();
00046 int nx = laserScan.getNormalsOffset();
00047 int ny = nx+1;
00048 int nz = ny+1;
00049 for(int i=0; i<laserScan.size(); ++i)
00050 {
00051 const float * ptr = laserScan.data().ptr<float>(0, i);
00052 float * out = output.ptr<float>(0, i);
00053 if(nx == -1)
00054 {
00055 pcl::PointXYZ pt(ptr[0], ptr[1], laserScan.is2d()?0:ptr[2]);
00056 pt = pcl::transformPoint(pt, transform3f);
00057 out[0] = pt.x;
00058 out[1] = pt.y;
00059 if(!laserScan.is2d())
00060 {
00061 out[2] = pt.z;
00062 }
00063 }
00064 else
00065 {
00066 pcl::PointNormal pt;
00067 pt.x=ptr[0];
00068 pt.y=ptr[1];
00069 pt.z=laserScan.is2d()?0:ptr[2];
00070 pt.normal_x=ptr[nx];
00071 pt.normal_y=ptr[ny];
00072 pt.normal_z=ptr[nz];
00073 pt = util3d::transformPoint(pt, transform);
00074 out[0] = pt.x;
00075 out[1] = pt.y;
00076 if(!laserScan.is2d())
00077 {
00078 out[2] = pt.z;
00079 }
00080 out[nx] = pt.normal_x;
00081 out[ny] = pt.normal_y;
00082 out[nz] = pt.normal_z;
00083 }
00084 }
00085 }
00086 return LaserScan(output, laserScan.maxPoints(), laserScan.maxRange(), laserScan.format(), laserScan.localTransform());
00087 }
00088
00089 pcl::PointCloud<pcl::PointXYZ>::Ptr transformPointCloud(
00090 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00091 const Transform & transform)
00092 {
00093 pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
00094 pcl::transformPointCloud(*cloud, *output, transform.toEigen4f());
00095 return output;
00096 }
00097 pcl::PointCloud<pcl::PointXYZI>::Ptr transformPointCloud(
00098 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
00099 const Transform & transform)
00100 {
00101 pcl::PointCloud<pcl::PointXYZI>::Ptr output(new pcl::PointCloud<pcl::PointXYZI>);
00102 pcl::transformPointCloud(*cloud, *output, transform.toEigen4f());
00103 return output;
00104 }
00105 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformPointCloud(
00106 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00107 const Transform & transform)
00108 {
00109 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGB>);
00110 pcl::transformPointCloud(*cloud, *output, transform.toEigen4f());
00111 return output;
00112 }
00113 pcl::PointCloud<pcl::PointNormal>::Ptr transformPointCloud(
00114 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00115 const Transform & transform)
00116 {
00117 pcl::PointCloud<pcl::PointNormal>::Ptr output(new pcl::PointCloud<pcl::PointNormal>);
00118 pcl::transformPointCloudWithNormals(*cloud, *output, transform.toEigen4f());
00119 return output;
00120 }
00121 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformPointCloud(
00122 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00123 const Transform & transform)
00124 {
00125 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00126 pcl::transformPointCloudWithNormals(*cloud, *output, transform.toEigen4f());
00127 return output;
00128 }
00129 pcl::PointCloud<pcl::PointXYZINormal>::Ptr transformPointCloud(
00130 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
00131 const Transform & transform)
00132 {
00133 pcl::PointCloud<pcl::PointXYZINormal>::Ptr output(new pcl::PointCloud<pcl::PointXYZINormal>);
00134 pcl::transformPointCloudWithNormals(*cloud, *output, transform.toEigen4f());
00135 return output;
00136 }
00137
00138 pcl::PointCloud<pcl::PointXYZ>::Ptr transformPointCloud(
00139 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
00140 const pcl::IndicesPtr & indices,
00141 const Transform & transform)
00142 {
00143 pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
00144 pcl::transformPointCloud(*cloud, *indices, *output, transform.toEigen4f());
00145 return output;
00146 }
00147 pcl::PointCloud<pcl::PointXYZI>::Ptr transformPointCloud(
00148 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
00149 const pcl::IndicesPtr & indices,
00150 const Transform & transform)
00151 {
00152 pcl::PointCloud<pcl::PointXYZI>::Ptr output(new pcl::PointCloud<pcl::PointXYZI>);
00153 pcl::transformPointCloud(*cloud, *indices, *output, transform.toEigen4f());
00154 return output;
00155 }
00156 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformPointCloud(
00157 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00158 const pcl::IndicesPtr & indices,
00159 const Transform & transform)
00160 {
00161 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGB>);
00162 pcl::transformPointCloud(*cloud, *indices, *output, transform.toEigen4f());
00163 return output;
00164 }
00165 pcl::PointCloud<pcl::PointNormal>::Ptr transformPointCloud(
00166 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
00167 const pcl::IndicesPtr & indices,
00168 const Transform & transform)
00169 {
00170 pcl::PointCloud<pcl::PointNormal>::Ptr output(new pcl::PointCloud<pcl::PointNormal>);
00171 pcl::transformPointCloudWithNormals(*cloud, *indices, *output, transform.toEigen4f());
00172 return output;
00173 }
00174 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformPointCloud(
00175 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
00176 const pcl::IndicesPtr & indices,
00177 const Transform & transform)
00178 {
00179 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00180 pcl::transformPointCloudWithNormals(*cloud, *indices, *output, transform.toEigen4f());
00181 return output;
00182 }
00183 pcl::PointCloud<pcl::PointXYZINormal>::Ptr transformPointCloud(
00184 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
00185 const pcl::IndicesPtr & indices,
00186 const Transform & transform)
00187 {
00188 pcl::PointCloud<pcl::PointXYZINormal>::Ptr output(new pcl::PointCloud<pcl::PointXYZINormal>);
00189 pcl::transformPointCloudWithNormals(*cloud, *indices, *output, transform.toEigen4f());
00190 return output;
00191 }
00192
00193 cv::Point3f transformPoint(
00194 const cv::Point3f & point,
00195 const Transform & transform)
00196 {
00197 cv::Point3f ret = point;
00198 ret.x = transform (0, 0) * point.x + transform (0, 1) * point.y + transform (0, 2) * point.z + transform (0, 3);
00199 ret.y = transform (1, 0) * point.x + transform (1, 1) * point.y + transform (1, 2) * point.z + transform (1, 3);
00200 ret.z = transform (2, 0) * point.x + transform (2, 1) * point.y + transform (2, 2) * point.z + transform (2, 3);
00201 return ret;
00202 }
00203 pcl::PointXYZ transformPoint(
00204 const pcl::PointXYZ & pt,
00205 const Transform & transform)
00206 {
00207 return pcl::transformPoint(pt, transform.toEigen3f());
00208 }
00209 pcl::PointXYZI transformPoint(
00210 const pcl::PointXYZI & pt,
00211 const Transform & transform)
00212 {
00213 return pcl::transformPoint(pt, transform.toEigen3f());
00214 }
00215 pcl::PointXYZRGB transformPoint(
00216 const pcl::PointXYZRGB & pt,
00217 const Transform & transform)
00218 {
00219 pcl::PointXYZRGB ptRGB = pcl::transformPoint(pt, transform.toEigen3f());
00220 ptRGB.rgb = pt.rgb;
00221 return ptRGB;
00222 }
00223 pcl::PointNormal transformPoint(
00224 const pcl::PointNormal & point,
00225 const Transform & transform)
00226 {
00227 pcl::PointNormal ret;
00228 Eigen::Matrix<float, 3, 1> pt (point.x, point.y, point.z);
00229 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));
00230 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));
00231 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));
00232
00233
00234 Eigen::Matrix<float, 3, 1> nt (point.normal_x, point.normal_y, point.normal_z);
00235 ret.normal_x = static_cast<float> (transform (0, 0) * nt.coeffRef (0) + transform (0, 1) * nt.coeffRef (1) + transform (0, 2) * nt.coeffRef (2));
00236 ret.normal_y = static_cast<float> (transform (1, 0) * nt.coeffRef (0) + transform (1, 1) * nt.coeffRef (1) + transform (1, 2) * nt.coeffRef (2));
00237 ret.normal_z = static_cast<float> (transform (2, 0) * nt.coeffRef (0) + transform (2, 1) * nt.coeffRef (1) + transform (2, 2) * nt.coeffRef (2));
00238 return ret;
00239 }
00240 pcl::PointXYZRGBNormal transformPoint(
00241 const pcl::PointXYZRGBNormal & point,
00242 const Transform & transform)
00243 {
00244 pcl::PointXYZRGBNormal ret;
00245 Eigen::Matrix<float, 3, 1> pt (point.x, point.y, point.z);
00246 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));
00247 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));
00248 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));
00249
00250
00251 Eigen::Matrix<float, 3, 1> nt (point.normal_x, point.normal_y, point.normal_z);
00252 ret.normal_x = static_cast<float> (transform (0, 0) * nt.coeffRef (0) + transform (0, 1) * nt.coeffRef (1) + transform (0, 2) * nt.coeffRef (2));
00253 ret.normal_y = static_cast<float> (transform (1, 0) * nt.coeffRef (0) + transform (1, 1) * nt.coeffRef (1) + transform (1, 2) * nt.coeffRef (2));
00254 ret.normal_z = static_cast<float> (transform (2, 0) * nt.coeffRef (0) + transform (2, 1) * nt.coeffRef (1) + transform (2, 2) * nt.coeffRef (2));
00255
00256 ret.rgb = point.rgb;
00257 return ret;
00258 }
00259 pcl::PointXYZINormal transformPoint(
00260 const pcl::PointXYZINormal & point,
00261 const Transform & transform)
00262 {
00263 pcl::PointXYZINormal ret;
00264 Eigen::Matrix<float, 3, 1> pt (point.x, point.y, point.z);
00265 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));
00266 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));
00267 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));
00268
00269
00270 Eigen::Matrix<float, 3, 1> nt (point.normal_x, point.normal_y, point.normal_z);
00271 ret.normal_x = static_cast<float> (transform (0, 0) * nt.coeffRef (0) + transform (0, 1) * nt.coeffRef (1) + transform (0, 2) * nt.coeffRef (2));
00272 ret.normal_y = static_cast<float> (transform (1, 0) * nt.coeffRef (0) + transform (1, 1) * nt.coeffRef (1) + transform (1, 2) * nt.coeffRef (2));
00273 ret.normal_z = static_cast<float> (transform (2, 0) * nt.coeffRef (0) + transform (2, 1) * nt.coeffRef (1) + transform (2, 2) * nt.coeffRef (2));
00274
00275 ret.intensity = point.intensity;
00276 return ret;
00277 }
00278
00279 }
00280
00281 }