3 #ifndef _RAPID_VIZ_PUBLISH_H_
4 #define _RAPID_VIZ_PUBLISH_H_
6 #include "opencv2/core/core.hpp"
7 #include "pcl/point_cloud.h"
8 #include "pcl/point_types.h"
10 #include "sensor_msgs/PointCloud2.h"
18 const std::string& frame_id =
"base_link");
21 const sensor_msgs::PointCloud2& cloud);
23 pcl::PointCloud<pcl::PointXYZ>& cloud);
25 pcl::PointCloud<pcl::PointXYZRGB>& cloud);
27 pcl::PointCloud<pcl::PointXYZRGBNormal>& cloud);
28 void PublishImage(
const ros::Publisher& pub,
const pcl::PCLHeader& cloud_header,
34 #endif // _RAPID_VIZ_PUBLISH_H_
void PublishBlankCloud(const ros::Publisher &pub, const std::string &frame_id="base_link")
void PublishImage(const ros::Publisher &pub, const pcl::PCLHeader &cloud_header, const cv::Mat &mat)
void PublishCloud(const ros::Publisher &pub, const sensor_msgs::PointCloud2 &cloud)