1 #ifndef _RAPID_PERCEPTION_CONVERSIONS_H_
2 #define _RAPID_PERCEPTION_CONVERSIONS_H_
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"
9 using sensor_msgs::PointCloud2;
10 using pcl::PointCloud;
11 using pcl::PointXYZRGB;
14 namespace perception {
15 PointCloud<PointXYZRGB>::Ptr
PclFromRos(
const PointCloud2& msg) {
16 PointCloud<PointXYZRGB>::Ptr out(
new PointCloud<PointXYZRGB>);
17 pcl::fromROSMsg(msg, *out);
21 PointCloud2::Ptr
RosFromPcl(PointCloud<PointXYZRGB>::Ptr cloud) {
22 PointCloud2::Ptr out(
new PointCloud2);
23 pcl::toROSMsg(*cloud, *out);
29 #endif // _RAPID_PERCEPTION_CONVERSIONS_H_
PointCloud< PointXYZRGB >::Ptr PclFromRos(const PointCloud2 &msg)
PointCloud2::Ptr RosFromPcl(PointCloud< PointXYZRGB >::Ptr cloud)