30 #include <pcl/common/transforms.h> 41 cv::Mat output = laserScan.
data().clone();
45 Eigen::Affine3f transform3f = transform.
toEigen3f();
49 for(
int i=0; i<laserScan.
size(); ++i)
51 const float * ptr = laserScan.
data().ptr<
float>(0, i);
52 float * out = output.ptr<
float>(0, i);
55 pcl::PointXYZ pt(ptr[0], ptr[1], laserScan.
is2d()?0:ptr[2]);
69 pt.z=laserScan.
is2d()?0:ptr[2];
80 out[nx] = pt.normal_x;
81 out[ny] = pt.normal_y;
82 out[nz] = pt.normal_z;
90 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
93 pcl::PointCloud<pcl::PointXYZ>::Ptr output(
new pcl::PointCloud<pcl::PointXYZ>);
98 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
101 pcl::PointCloud<pcl::PointXYZI>::Ptr output(
new pcl::PointCloud<pcl::PointXYZI>);
106 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
109 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(
new pcl::PointCloud<pcl::PointXYZRGB>);
114 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
117 pcl::PointCloud<pcl::PointNormal>::Ptr output(
new pcl::PointCloud<pcl::PointNormal>);
118 pcl::transformPointCloudWithNormals(*cloud, *output, transform.
toEigen4f());
122 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
125 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr output(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
126 pcl::transformPointCloudWithNormals(*cloud, *output, transform.
toEigen4f());
130 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
133 pcl::PointCloud<pcl::PointXYZINormal>::Ptr output(
new pcl::PointCloud<pcl::PointXYZINormal>);
134 pcl::transformPointCloudWithNormals(*cloud, *output, transform.
toEigen4f());
139 const pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud,
140 const pcl::IndicesPtr & indices,
143 pcl::PointCloud<pcl::PointXYZ>::Ptr output(
new pcl::PointCloud<pcl::PointXYZ>);
148 const pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud,
149 const pcl::IndicesPtr & indices,
152 pcl::PointCloud<pcl::PointXYZI>::Ptr output(
new pcl::PointCloud<pcl::PointXYZI>);
157 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
158 const pcl::IndicesPtr & indices,
161 pcl::PointCloud<pcl::PointXYZRGB>::Ptr output(
new pcl::PointCloud<pcl::PointXYZRGB>);
166 const pcl::PointCloud<pcl::PointNormal>::Ptr & cloud,
167 const pcl::IndicesPtr & indices,
170 pcl::PointCloud<pcl::PointNormal>::Ptr output(
new pcl::PointCloud<pcl::PointNormal>);
171 pcl::transformPointCloudWithNormals(*cloud, *indices, *output, transform.
toEigen4f());
175 const pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud,
176 const pcl::IndicesPtr & indices,
179 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr output(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
180 pcl::transformPointCloudWithNormals(*cloud, *indices, *output, transform.
toEigen4f());
184 const pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud,
185 const pcl::IndicesPtr & indices,
188 pcl::PointCloud<pcl::PointXYZINormal>::Ptr output(
new pcl::PointCloud<pcl::PointXYZINormal>);
189 pcl::transformPointCloudWithNormals(*cloud, *indices, *output, transform.
toEigen4f());
194 const cv::Point3f & point,
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);
204 const pcl::PointXYZ & pt,
210 const pcl::PointXYZI & pt,
216 const pcl::PointXYZRGB & pt,
224 const pcl::PointNormal & point,
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));
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));
241 const pcl::PointXYZRGBNormal & point,
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));
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));
260 const pcl::PointXYZINormal & point,
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));
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));
275 ret.intensity = point.intensity;
cv::Point3f RTABMAP_EXP transformPoint(const cv::Point3f &pt, const Transform &transform)
const cv::Mat & data() const
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
int getNormalsOffset() const
LaserScan RTABMAP_EXP transformLaserScan(const LaserScan &laserScan, const Transform &transform)
Transform localTransform() const
ULogger class and convenient macros.