rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
conversions.h
Go to the documentation of this file.
1 #ifndef _RAPID_PERCEPTION_CONVERSIONS_H_
2 #define _RAPID_PERCEPTION_CONVERSIONS_H_
3 
4 #include "pcl/point_cloud.h"
5 #include "pcl/point_types.h"
6 #include "pcl_conversions/pcl_conversions.h"
7 #include "sensor_msgs/PointCloud2.h"
8 
9 using sensor_msgs::PointCloud2;
10 using pcl::PointCloud;
11 using pcl::PointXYZRGB;
12 
13 namespace rapid {
14 namespace perception {
15 PointCloud<PointXYZRGB>::Ptr PclFromRos(const PointCloud2& msg) {
16  PointCloud<PointXYZRGB>::Ptr out(new PointCloud<PointXYZRGB>);
17  pcl::fromROSMsg(msg, *out);
18  return out;
19 }
20 
21 PointCloud2::Ptr RosFromPcl(PointCloud<PointXYZRGB>::Ptr cloud) {
22  PointCloud2::Ptr out(new PointCloud2);
23  pcl::toROSMsg(*cloud, *out);
24  return out;
25 }
26 } // namespace perception
27 } // namespace rapid
28 
29 #endif // _RAPID_PERCEPTION_CONVERSIONS_H_
PointCloud< PointXYZRGB >::Ptr PclFromRos(const PointCloud2 &msg)
Definition: conversions.h:15
PointCloud2::Ptr RosFromPcl(PointCloud< PointXYZRGB >::Ptr cloud)
Definition: conversions.h:21