rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
publish.h
Go to the documentation of this file.
1 // Containers functions to publish common data formats.
2 
3 #ifndef _RAPID_VIZ_PUBLISH_H_
4 #define _RAPID_VIZ_PUBLISH_H_
5 
6 #include "opencv2/core/core.hpp"
7 #include "pcl/point_cloud.h"
8 #include "pcl/point_types.h"
9 #include "ros/ros.h"
10 #include "sensor_msgs/PointCloud2.h"
11 
12 namespace rapid {
13 namespace viz {
14 // Publish a blank point cloud to "erase" a point cloud display on a latched
15 // topic. If your task context doesn't have a base_link frame, set frame_id to
16 // whatever frame you can visualize with.
17 void PublishBlankCloud(const ros::Publisher& pub,
18  const std::string& frame_id = "base_link");
19 // Publish a point cloud using the given publisher.
20 void PublishCloud(const ros::Publisher& pub,
21  const sensor_msgs::PointCloud2& cloud);
22 void PublishCloud(const ros::Publisher& pub,
23  pcl::PointCloud<pcl::PointXYZ>& cloud);
24 void PublishCloud(const ros::Publisher& pub,
25  pcl::PointCloud<pcl::PointXYZRGB>& cloud);
26 void PublishCloud(const ros::Publisher& pub,
27  pcl::PointCloud<pcl::PointXYZRGBNormal>& cloud);
28 void PublishImage(const ros::Publisher& pub, const pcl::PCLHeader& cloud_header,
29  const cv::Mat& mat);
30 
31 } // namespace viz
32 } // namespace rapid
33 
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)