37 #ifndef pcl_ros_IMPL_TRANSFORMS_H_
38 #define pcl_ros_IMPL_TRANSFORMS_H_
50 template <
typename Po
intT>
void
52 pcl::PointCloud <PointT> &cloud_out,
const tf::Transform &transform)
60 Eigen::Quaternionf rotation (q.w (), q.x (), q.y (), q.z ());
62 Eigen::Vector3f origin (v.x (), v.y (), v.z ());
71 template <
typename Po
intT>
void
73 pcl::PointCloud <PointT> &cloud_out,
const geometry_msgs::Transform &transform)
75 Eigen::Quaterniond rotation;
77 Eigen::Vector3d origin;
84 template <
typename Po
intT>
void
86 pcl::PointCloud <PointT> &cloud_out,
const tf::Transform &transform)
94 Eigen::Quaternionf rotation (q.w (), q.x (), q.y (), q.z ());
96 Eigen::Vector3f origin (v.x (), v.y (), v.z ());
105 template <
typename Po
intT>
void
107 pcl::PointCloud <PointT> &cloud_out,
const geometry_msgs::Transform &transform)
109 Eigen::Quaterniond rotation;
111 Eigen::Vector3d origin;
118 template <
typename Po
intT>
bool
120 const pcl::PointCloud <PointT> &cloud_in,
121 pcl::PointCloud <PointT> &cloud_out,
124 if (cloud_in.header.frame_id == target_frame)
126 cloud_out = cloud_in;
133 tf_listener.
lookupTransform (target_frame, cloud_in.header.frame_id,
fromPCL(cloud_in.header).stamp, transform);
142 cloud_out.header.frame_id = target_frame;
147 template <
typename Po
intT>
bool
149 const pcl::PointCloud <PointT> &cloud_in,
150 pcl::PointCloud <PointT> &cloud_out,
153 if (cloud_in.header.frame_id == target_frame)
155 cloud_out = cloud_in;
159 geometry_msgs::TransformStamped transform;
162 transform = tf_buffer.
lookupTransform (target_frame, cloud_in.header.frame_id,
fromPCL(cloud_in.header).stamp);
176 cloud_out.header.frame_id = target_frame;
181 template <
typename Po
intT>
bool
183 const pcl::PointCloud <PointT> &cloud_in,
184 pcl::PointCloud <PointT> &cloud_out,
187 if (cloud_in.header.frame_id == target_frame)
189 cloud_out = cloud_in;
196 tf_listener.
lookupTransform (target_frame, cloud_in.header.frame_id,
fromPCL(cloud_in.header).stamp, transform);
205 cloud_out.header.frame_id = target_frame;
210 template <
typename Po
intT>
bool
212 const pcl::PointCloud <PointT> &cloud_in,
213 pcl::PointCloud <PointT> &cloud_out,
216 if (cloud_in.header.frame_id == target_frame)
218 cloud_out = cloud_in;
222 geometry_msgs::TransformStamped transform;
225 transform = tf_buffer.
lookupTransform (target_frame, cloud_in.header.frame_id,
fromPCL(cloud_in.header).stamp);
238 cloud_out.header.frame_id = target_frame;
243 template <
typename Po
intT>
bool
246 const pcl::PointCloud <PointT> &cloud_in,
247 const std::string &fixed_frame,
248 pcl::PointCloud <PointT> &cloud_out,
254 tf_listener.
lookupTransform (target_frame, target_time, cloud_in.header.frame_id,
fromPCL(cloud_in.header).stamp, fixed_frame, transform);
263 cloud_out.header.frame_id = target_frame;
264 cloud_out.header.seq = cloud_in.header.seq;
265 cloud_out.header.stamp =
toPCL(target_time);
270 template <
typename Po
intT>
bool
273 const pcl::PointCloud <PointT> &cloud_in,
274 const std::string &fixed_frame,
275 pcl::PointCloud <PointT> &cloud_out,
278 geometry_msgs::TransformStamped transform;
281 transform = tf_buffer.
lookupTransform (target_frame, target_time, cloud_in.header.frame_id,
fromPCL(cloud_in.header).stamp, fixed_frame);
295 cloud_out.header.frame_id = target_frame;
296 cloud_out.header.seq = cloud_in.header.seq;
297 cloud_out.header.stamp =
toPCL(target_time);
302 template <
typename Po
intT>
bool
305 const pcl::PointCloud <PointT> &cloud_in,
306 const std::string &fixed_frame,
307 pcl::PointCloud <PointT> &cloud_out,
313 tf_listener.
lookupTransform (target_frame, target_time, cloud_in.header.frame_id,
fromPCL(cloud_in.header).stamp, fixed_frame, transform);
322 cloud_out.header.frame_id = target_frame;
323 cloud_out.header.seq = cloud_in.header.seq;
324 cloud_out.header.stamp =
toPCL(target_time);
329 template <
typename Po
intT>
bool
332 const pcl::PointCloud <PointT> &cloud_in,
333 const std::string &fixed_frame,
334 pcl::PointCloud <PointT> &cloud_out,
337 geometry_msgs::TransformStamped transform;
340 transform = tf_buffer.
lookupTransform (target_frame, target_time, cloud_in.header.frame_id,
fromPCL(cloud_in.header).stamp, fixed_frame);
354 cloud_out.header.frame_id = target_frame;
355 cloud_out.header.seq = cloud_in.header.seq;
356 cloud_out.header.stamp =
toPCL(target_time);