rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
cloud_projection.h
Go to the documentation of this file.
1 #ifndef _RAPID_PERCEPTION_CLOUD_PROJECTION_H_
2 #define _RAPID_PERCEPTION_CLOUD_PROJECTION_H_
3 
4 #include "opencv2/core/core.hpp"
5 #include "pcl/PointIndices.h"
6 #include "pcl/point_cloud.h"
7 #include "pcl/point_types.h"
8 #include "sensor_msgs/CameraInfo.h"
9 
10 namespace rapid {
11 namespace perception {
12 // Projects the given point cloud onto the image plane.
13 void CloudToImage(const sensor_msgs::CameraInfo& camera_info,
14  const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
15  cv::Mat* image);
16 void CloudToImage(const sensor_msgs::CameraInfo& camera_info,
17  const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
18  const pcl::PointIndices::Ptr& indices, cv::Mat* image);
19 
20 // Returns the standard CameraInfo value for the head-mounted Kinect 360 on the
21 // PR2.
22 sensor_msgs::CameraInfo HeadMountKinectCameraInfo();
23 } // namespace perception
24 } // namespace rapid
25 
26 #endif // _RAPID_PERCEPTION_CLOUD_PROJECTION_H_
void CloudToImage(const sensor_msgs::CameraInfo &camera_info, const pcl::PointCloud< pcl::PointXYZRGB > &cloud, cv::Mat *image)
sensor_msgs::CameraInfo HeadMountKinectCameraInfo()