$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::PointXYZRGB point_type; 00019 typedef pcl::PointCloud<point_type> pointcloud_type; 00020 typedef mf::sync_policies::ApproximateTime<sm::Image, sm::Image, sm::CameraInfo> NoCloudSyncPolicy; 00021 00023 typedef union 00024 { 00025 struct /*anonymous*/ 00026 { 00027 unsigned char Blue; 00028 unsigned char Green; 00029 unsigned char Red; 00030 unsigned char Alpha; 00031 }; 00032 float float_value; 00033 long long_value; 00034 } RGBValue; 00035 00037 pointcloud_type* createPointCloud (const sm::ImageConstPtr& depth_msg, 00038 const sm::ImageConstPtr& rgb_msg, 00039 const sm::CameraInfoConstPtr& cam_info) 00040 { 00041 pointcloud_type* cloud (new pointcloud_type() ); 00042 cloud->header.stamp = depth_msg->header.stamp; 00043 cloud->header.frame_id = depth_msg->header.frame_id; 00044 cloud->is_dense = true; //single point of view, 2d rasterized 00045 00046 float cx, cy, fx, fy;//principal point and focal lengths 00047 unsigned color_step = 0, color_skip = 0; 00048 00049 cloud->height = depth_msg->height; 00050 cloud->width = depth_msg->width; 00051 cx = cam_info->K[2]; //(cloud->width >> 1) - 0.5f; 00052 cy = cam_info->K[5]; //(cloud->height >> 1) - 0.5f; 00053 fx = 1.0f / cam_info->K[0]; 00054 fy = 1.0f / cam_info->K[4]; 00055 int pixel_data_size = 3; 00056 char red_idx = 0, green_idx = 1, blue_idx = 2; 00057 00058 if(rgb_msg->encoding.compare("mono8") == 0) pixel_data_size = 1; 00059 if(rgb_msg->encoding.compare("bgr8") == 0) { red_idx = 2; blue_idx = 0; } 00060 00061 ROS_ERROR_COND(pixel_data_size == 0, "Unknown image encoding: %s!", rgb_msg->encoding.c_str()); 00062 color_step = pixel_data_size * rgb_msg->width / cloud->width; 00063 color_skip = pixel_data_size * (rgb_msg->height / cloud->height - 1) * rgb_msg->width; 00064 00065 cloud->points.resize (cloud->height * cloud->width); 00066 00067 const float* depth_buffer = reinterpret_cast<const float*>(&depth_msg->data[0]); 00068 const uint8_t* rgb_buffer = &rgb_msg->data[0]; 00069 00070 // depth_msg already has the desired dimensions, but rgb_msg may be higher res. 00071 int color_idx = 0, depth_idx = 0; 00072 00073 pointcloud_type::iterator pt_iter = cloud->begin (); 00074 for (int v = 0; v < (int)cloud->height; ++v, color_idx += color_skip) 00075 { 00076 for (int u = 0; u < (int)cloud->width; ++u, color_idx += color_step, ++depth_idx, ++pt_iter) 00077 { 00078 point_type& pt = *pt_iter; 00079 float Z = depth_buffer[depth_idx]; 00080 00081 // Check for invalid measurements 00082 if (std::isnan (Z)) 00083 { 00084 pt.x = pt.y = pt.z = Z; 00085 } 00086 else // Fill in XYZ 00087 { 00088 pt.x = (u - cx) * Z * fx; 00089 pt.y = (v - cy) * Z * fy; 00090 pt.z = Z; 00091 } 00092 00093 if(rgb_msg.get() != 0){ 00094 // Fill in color 00095 RGBValue color; 00096 if(pixel_data_size == 3){ 00097 color.Red = rgb_buffer[color_idx + red_idx]; 00098 color.Green = rgb_buffer[color_idx + green_idx]; 00099 color.Blue = rgb_buffer[color_idx + blue_idx]; 00100 } else { 00101 color.Red = color.Green = color.Blue = rgb_buffer[color_idx]; 00102 } 00103 color.Alpha = 0; 00104 pt.rgb = color.float_value; 00105 } 00106 } 00107 } 00108 00109 return cloud; 00110 } 00111 00112 00113 void rgbd_callback(const sm::ImageConstPtr& rgbimage, 00114 const sm::ImageConstPtr& dimage, 00115 const sm::CameraInfoConstPtr& cam_info, 00116 ros::Publisher* cloud_pub) 00117 { 00118 pointcloud_type* pc = createPointCloud(dimage, rgbimage, cam_info); 00119 sm::PointCloud2 cloudMessage; 00120 pcl::toROSMsg(*pc,cloudMessage); 00121 cloud_pub->publish(cloudMessage); 00122 delete pc; 00123 } 00124 00125 int main(int argc, char** argv) 00126 { 00127 ros::init(argc, argv, "rgbd2cloud"); 00128 ros::NodeHandle nh; 00129 ros::Publisher pc_pub = nh.advertise<sm::PointCloud2>("cloud_out", 10); 00130 ROS_INFO("To reconstruct point clouds from openni images call this tool as follows:\nrosrun rgbd2cloud rgbd2cloud rgb_image:=/camera/rgb/image_color depth_image:=/camera/depth/image camera_info:=/camera/depth/camera_info"); 00131 00132 //Subscribers 00133 mf::Subscriber<sm::Image> rgb_sub(nh, "rgb_image", 2); 00134 mf::Subscriber<sm::Image> depth_sub(nh, "depth_image", 2); 00135 mf::Subscriber<sm::CameraInfo> info_sub(nh, "camera_info", 5); 00136 00137 //Syncronize rgb, depth and calibration 00138 mf::Synchronizer<NoCloudSyncPolicy> no_cloud_sync(NoCloudSyncPolicy(2), rgb_sub, depth_sub, info_sub); 00139 no_cloud_sync.registerCallback(boost::bind(&rgbd_callback, _1, _2, _3, &pc_pub)); 00140 00141 ros::spin(); 00142 return 0; 00143 } 00144