util3d_transforms.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
29 
30 #include <pcl/common/transforms.h>
32 
33 namespace rtabmap
34 {
35 
36 namespace util3d
37 {
38 
39 LaserScan transformLaserScan(const LaserScan & laserScan, const Transform & transform)
40 {
41  cv::Mat output = laserScan.data().clone();
42 
43  if(!transform.isNull() && !transform.isIdentity())
44  {
45  Eigen::Affine3f transform3f = transform.toEigen3f();
46  int nx = laserScan.getNormalsOffset();
47  int ny = nx+1;
48  int nz = ny+1;
49  for(int i=0; i<laserScan.size(); ++i)
50  {
51  const float * ptr = laserScan.data().ptr<float>(0, i);
52  float * out = output.ptr<float>(0, i);
53  if(nx == -1)
54  {
55  pcl::PointXYZ pt(ptr[0], ptr[1], laserScan.is2d()?0:ptr[2]);
56  pt = pcl::transformPoint(pt, transform3f);
57  out[0] = pt.x;
58  out[1] = pt.y;
59  if(!laserScan.is2d())
60  {
61  out[2] = pt.z;
62  }
63  }
64  else
65  {
66  pcl::PointNormal pt;
67  pt.x=ptr[0];
68  pt.y=ptr[1];
69  pt.z=laserScan.is2d()?0:ptr[2];
70  pt.normal_x=ptr[nx];
71  pt.normal_y=ptr[ny];
72  pt.normal_z=ptr[nz];
73  pt = util3d::transformPoint(pt, transform);
74  out[0] = pt.x;
75  out[1] = pt.y;
76  if(!laserScan.is2d())
77  {
78  out[2] = pt.z;
79  }
80  out[nx] = pt.normal_x;
81  out[ny] = pt.normal_y;
82  out[nz] = pt.normal_z;
83  }
84  }
85  }
86  return LaserScan(output, laserScan.maxPoints(), laserScan.maxRange(), laserScan.format(), laserScan.localTransform());
87 }
88 
89 pcl::PointCloud<pcl::PointXYZ>::Ptr transformPointCloud(
90  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
91  const Transform & transform)
92 {
93  pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
94  pcl::transformPointCloud(*cloud, *output, transform.toEigen4f());
95  return output;
96 }
97 pcl::PointCloud<pcl::PointXYZI>::Ptr transformPointCloud(
98  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
99  const Transform & transform)
100 {
101  pcl::PointCloud<pcl::PointXYZI>::Ptr output(new pcl::PointCloud<pcl::PointXYZI>);
102  pcl::transformPointCloud(*cloud, *output, transform.toEigen4f());
103  return output;
104 }
105 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformPointCloud(
106  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
107  const Transform & transform)
108 {
109  pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGB>);
110  pcl::transformPointCloud(*cloud, *output, transform.toEigen4f());
111  return output;
112 }
113 pcl::PointCloud<pcl::PointNormal>::Ptr transformPointCloud(
114  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
115  const Transform & transform)
116 {
117  pcl::PointCloud<pcl::PointNormal>::Ptr output(new pcl::PointCloud<pcl::PointNormal>);
118  pcl::transformPointCloudWithNormals(*cloud, *output, transform.toEigen4f());
119  return output;
120 }
121 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformPointCloud(
122  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
123  const Transform & transform)
124 {
125  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
126  pcl::transformPointCloudWithNormals(*cloud, *output, transform.toEigen4f());
127  return output;
128 }
129 pcl::PointCloud<pcl::PointXYZINormal>::Ptr transformPointCloud(
130  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
131  const Transform & transform)
132 {
133  pcl::PointCloud<pcl::PointXYZINormal>::Ptr output(new pcl::PointCloud<pcl::PointXYZINormal>);
134  pcl::transformPointCloudWithNormals(*cloud, *output, transform.toEigen4f());
135  return output;
136 }
137 
138 pcl::PointCloud<pcl::PointXYZ>::Ptr transformPointCloud(
139  const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
140  const pcl::IndicesPtr & indices,
141  const Transform & transform)
142 {
143  pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
144  pcl::transformPointCloud(*cloud, *indices, *output, transform.toEigen4f());
145  return output;
146 }
147 pcl::PointCloud<pcl::PointXYZI>::Ptr transformPointCloud(
148  const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
149  const pcl::IndicesPtr & indices,
150  const Transform & transform)
151 {
152  pcl::PointCloud<pcl::PointXYZI>::Ptr output(new pcl::PointCloud<pcl::PointXYZI>);
153  pcl::transformPointCloud(*cloud, *indices, *output, transform.toEigen4f());
154  return output;
155 }
156 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformPointCloud(
157  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
158  const pcl::IndicesPtr & indices,
159  const Transform & transform)
160 {
161  pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGB>);
162  pcl::transformPointCloud(*cloud, *indices, *output, transform.toEigen4f());
163  return output;
164 }
165 pcl::PointCloud<pcl::PointNormal>::Ptr transformPointCloud(
166  const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
167  const pcl::IndicesPtr & indices,
168  const Transform & transform)
169 {
170  pcl::PointCloud<pcl::PointNormal>::Ptr output(new pcl::PointCloud<pcl::PointNormal>);
171  pcl::transformPointCloudWithNormals(*cloud, *indices, *output, transform.toEigen4f());
172  return output;
173 }
174 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr transformPointCloud(
175  const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
176  const pcl::IndicesPtr & indices,
177  const Transform & transform)
178 {
179  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr output(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
180  pcl::transformPointCloudWithNormals(*cloud, *indices, *output, transform.toEigen4f());
181  return output;
182 }
183 pcl::PointCloud<pcl::PointXYZINormal>::Ptr transformPointCloud(
184  const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
185  const pcl::IndicesPtr & indices,
186  const Transform & transform)
187 {
188  pcl::PointCloud<pcl::PointXYZINormal>::Ptr output(new pcl::PointCloud<pcl::PointXYZINormal>);
189  pcl::transformPointCloudWithNormals(*cloud, *indices, *output, transform.toEigen4f());
190  return output;
191 }
192 
193 cv::Point3f transformPoint(
194  const cv::Point3f & point,
195  const Transform & transform)
196 {
197  cv::Point3f ret = point;
198  ret.x = transform (0, 0) * point.x + transform (0, 1) * point.y + transform (0, 2) * point.z + transform (0, 3);
199  ret.y = transform (1, 0) * point.x + transform (1, 1) * point.y + transform (1, 2) * point.z + transform (1, 3);
200  ret.z = transform (2, 0) * point.x + transform (2, 1) * point.y + transform (2, 2) * point.z + transform (2, 3);
201  return ret;
202 }
203 pcl::PointXYZ transformPoint(
204  const pcl::PointXYZ & pt,
205  const Transform & transform)
206 {
207  return pcl::transformPoint(pt, transform.toEigen3f());
208 }
209 pcl::PointXYZI transformPoint(
210  const pcl::PointXYZI & pt,
211  const Transform & transform)
212 {
213  return pcl::transformPoint(pt, transform.toEigen3f());
214 }
215 pcl::PointXYZRGB transformPoint(
216  const pcl::PointXYZRGB & pt,
217  const Transform & transform)
218 {
219  pcl::PointXYZRGB ptRGB = pcl::transformPoint(pt, transform.toEigen3f());
220  ptRGB.rgb = pt.rgb;
221  return ptRGB;
222 }
223 pcl::PointNormal transformPoint(
224  const pcl::PointNormal & point,
225  const Transform & transform)
226 {
227  pcl::PointNormal ret;
228  Eigen::Matrix<float, 3, 1> pt (point.x, point.y, point.z);
229  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));
230  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));
231  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));
232 
233  // Rotate normals
234  Eigen::Matrix<float, 3, 1> nt (point.normal_x, point.normal_y, point.normal_z);
235  ret.normal_x = static_cast<float> (transform (0, 0) * nt.coeffRef (0) + transform (0, 1) * nt.coeffRef (1) + transform (0, 2) * nt.coeffRef (2));
236  ret.normal_y = static_cast<float> (transform (1, 0) * nt.coeffRef (0) + transform (1, 1) * nt.coeffRef (1) + transform (1, 2) * nt.coeffRef (2));
237  ret.normal_z = static_cast<float> (transform (2, 0) * nt.coeffRef (0) + transform (2, 1) * nt.coeffRef (1) + transform (2, 2) * nt.coeffRef (2));
238  return ret;
239 }
240 pcl::PointXYZRGBNormal transformPoint(
241  const pcl::PointXYZRGBNormal & point,
242  const Transform & transform)
243 {
244  pcl::PointXYZRGBNormal ret;
245  Eigen::Matrix<float, 3, 1> pt (point.x, point.y, point.z);
246  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));
247  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));
248  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));
249 
250  // Rotate normals
251  Eigen::Matrix<float, 3, 1> nt (point.normal_x, point.normal_y, point.normal_z);
252  ret.normal_x = static_cast<float> (transform (0, 0) * nt.coeffRef (0) + transform (0, 1) * nt.coeffRef (1) + transform (0, 2) * nt.coeffRef (2));
253  ret.normal_y = static_cast<float> (transform (1, 0) * nt.coeffRef (0) + transform (1, 1) * nt.coeffRef (1) + transform (1, 2) * nt.coeffRef (2));
254  ret.normal_z = static_cast<float> (transform (2, 0) * nt.coeffRef (0) + transform (2, 1) * nt.coeffRef (1) + transform (2, 2) * nt.coeffRef (2));
255 
256  ret.rgb = point.rgb;
257  return ret;
258 }
259 pcl::PointXYZINormal transformPoint(
260  const pcl::PointXYZINormal & point,
261  const Transform & transform)
262 {
263  pcl::PointXYZINormal ret;
264  Eigen::Matrix<float, 3, 1> pt (point.x, point.y, point.z);
265  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));
266  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));
267  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));
268 
269  // Rotate normals
270  Eigen::Matrix<float, 3, 1> nt (point.normal_x, point.normal_y, point.normal_z);
271  ret.normal_x = static_cast<float> (transform (0, 0) * nt.coeffRef (0) + transform (0, 1) * nt.coeffRef (1) + transform (0, 2) * nt.coeffRef (2));
272  ret.normal_y = static_cast<float> (transform (1, 0) * nt.coeffRef (0) + transform (1, 1) * nt.coeffRef (1) + transform (1, 2) * nt.coeffRef (2));
273  ret.normal_z = static_cast<float> (transform (2, 0) * nt.coeffRef (0) + transform (2, 1) * nt.coeffRef (1) + transform (2, 2) * nt.coeffRef (2));
274 
275  ret.intensity = point.intensity;
276  return ret;
277 }
278 
279 }
280 
281 }
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
const cv::Mat & data() const
Definition: LaserScan.h:63
Format format() const
Definition: LaserScan.h:66
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
float maxRange() const
Definition: LaserScan.h:65
int maxPoints() const
Definition: LaserScan.h:64
int getNormalsOffset() const
Definition: LaserScan.h:81
bool is2d() const
Definition: LaserScan.h:72
int size() const
Definition: LaserScan.h:70
bool isIdentity() const
Definition: Transform.cpp:136
bool isNull() const
Definition: Transform.cpp:107
LaserScan RTABMAP_EXP transformLaserScan(const LaserScan &laserScan, const Transform &transform)
Transform localTransform() const
Definition: LaserScan.h:67
Eigen::Matrix4f toEigen4f() const
Definition: Transform.cpp:325
ULogger class and convenient macros.
Eigen::Affine3f toEigen3f() const
Definition: Transform.cpp:344


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:41