$search
00001 #include <message_filters/subscriber.h> 00002 #include <message_filters/synchronizer.h> 00003 #include <message_filters/sync_policies/approximate_time.h> 00004 #include <sensor_msgs/Image.h> 00005 #include <sensor_msgs/CameraInfo.h> 00006 #include <sensor_msgs/PointCloud2.h> 00007 #include <string> 00008 #include <ros/ros.h> 00009 00010 //this is a global definition of the points to be used 00011 //changes to omit color would need adaptations in 00012 //the visualization too 00013 #include <pcl/io/io.h> 00014 #include "pcl/point_cloud.h" 00015 #include "pcl/point_types.h" 00016 namespace sm = sensor_msgs; 00017 namespace mf = message_filters; 00018 typedef pcl::PointXYZ point_type; 00019 typedef pcl::PointCloud<point_type> pointcloud_type; 00020 typedef mf::sync_policies::ApproximateTime<sm::Image, sm::CameraInfo> NoCloudSyncPolicy; 00021 00023 pointcloud_type* createPointCloud (const sm::ImageConstPtr& depth_msg, 00024 const sm::CameraInfoConstPtr& cam_info) 00025 { 00026 pointcloud_type* cloud (new pointcloud_type() ); 00027 cloud->header.stamp = depth_msg->header.stamp; 00028 cloud->header.frame_id = depth_msg->header.frame_id; 00029 cloud->is_dense = true; //single point of view, 2d rasterized 00030 00031 float cx, cy, fx, fy;//principal point and focal lengths 00032 00033 cloud->height = depth_msg->height; 00034 cloud->width = depth_msg->width; 00035 cx = cam_info->K[2]; //(cloud->width >> 1) - 0.5f; 00036 cy = cam_info->K[5]; //(cloud->height >> 1) - 0.5f; 00037 fx = 1.0f / cam_info->K[0]; 00038 fy = 1.0f / cam_info->K[4]; 00039 00040 cloud->points.resize (cloud->height * cloud->width); 00041 00042 const float* depth_buffer = reinterpret_cast<const float*>(&depth_msg->data[0]); 00043 00044 int depth_idx = 0; 00045 00046 pointcloud_type::iterator pt_iter = cloud->begin (); 00047 for (int v = 0; v < (int)cloud->height; ++v) 00048 { 00049 for (int u = 0; u < (int)cloud->width; ++u, ++depth_idx, ++pt_iter) 00050 { 00051 point_type& pt = *pt_iter; 00052 float Z = depth_buffer[depth_idx]; 00053 00054 // Check for invalid measurements 00055 if (std::isnan (Z)) 00056 { 00057 pt.x = pt.y = pt.z = Z; 00058 } 00059 else // Fill in XYZ 00060 { 00061 pt.x = (u - cx) * Z * fx; 00062 pt.y = (v - cy) * Z * fy; 00063 pt.z = Z; 00064 } 00065 00066 } 00067 } 00068 00069 return cloud; 00070 } 00071 00072 00073 void depth_callback(const sm::ImageConstPtr& dimage, 00074 const sm::CameraInfoConstPtr& cam_info, 00075 ros::Publisher* cloud_pub) 00076 { 00077 pointcloud_type* pc = createPointCloud(dimage, cam_info); 00078 sm::PointCloud2 cloudMessage; 00079 pcl::toROSMsg(*pc,cloudMessage); 00080 cloud_pub->publish(cloudMessage); 00081 delete pc; 00082 } 00083 00084 int main(int argc, char** argv) 00085 { 00086 ros::init(argc, argv, "depth2cloud"); 00087 ros::NodeHandle nh; 00088 ros::Publisher pc_pub = nh.advertise<sm::PointCloud2>("cloud_out", 10); 00089 ROS_INFO("To reconstruct point clouds from openni depth images call this tool as follows:\nrosrun depth2cloud depth2cloud depth_image:=/camera/depth/image camera_info:=/camera/depth/camera_info"); 00090 00091 //Subscribers 00092 mf::Subscriber<sm::Image> depth_sub(nh, "depth_image", 2); 00093 mf::Subscriber<sm::CameraInfo> info_sub(nh, "camera_info", 5); 00094 00095 //Syncronize depth and calibration 00096 mf::Synchronizer<NoCloudSyncPolicy> no_cloud_sync(NoCloudSyncPolicy(2), depth_sub, info_sub); 00097 no_cloud_sync.registerCallback(boost::bind(&depth_callback, _1, _2, &pc_pub)); 00098 00099 ros::spin(); 00100 return 0; 00101 } 00102