00001 /* 00002 * Copyright (c) 2009, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 #include <ros/ros.h> 00031 00032 #include <sensor_msgs/Image.h> 00033 #include <sensor_msgs/CameraInfo.h> 00034 #include <stereo_msgs/DisparityImage.h> 00035 #include <sensor_msgs/PointCloud2.h> 00036 00037 #include "rgbd_assembler/msg_saver.h" 00038 #include "rgbd_assembler/RgbdAssembly.h" 00039 00040 namespace rgbd_assembler 00041 { 00042 00043 class RgdbAssemblerKinect 00044 { 00045 00046 private: 00048 ros::NodeHandle root_nh_; 00050 ros::NodeHandle priv_nh_; 00051 00052 ros::ServiceServer rgbd_srv_; 00053 00054 //------------------ Callbacks ------------------- 00055 00057 bool rgbdServiceCallback( RgbdAssembly::Request &request, 00058 RgbdAssembly::Response &response ); 00059 00060 //------------------ Individual processing steps ------- 00061 bool assembleSensorData( ros::Duration time_out ); 00062 00063 // ------------------- The Data -------------- 00064 00065 sensor_msgs::Image image_; 00066 stereo_msgs::DisparityImage disparity_image_; 00067 sensor_msgs::CameraInfo cam_info_; 00068 sensor_msgs::PointCloud2 point_cloud_; 00069 00070 public: 00071 00072 RgdbAssemblerKinect() : 00073 root_nh_(""), priv_nh_("~") 00074 { 00075 rgbd_srv_ = root_nh_.advertiseService( 00076 root_nh_.resolveName("/rgbd_assembly"), 00077 &RgdbAssemblerKinect::rgbdServiceCallback, this); 00078 00079 ROS_INFO("RGB-D Kinect Assembler node started"); 00080 } 00081 00082 ~RgdbAssemblerKinect() 00083 { 00084 } 00085 00086 }; 00087 00088 bool RgdbAssemblerKinect::rgbdServiceCallback( RgbdAssembly::Request &request, 00089 RgbdAssembly::Response &response ) 00090 { 00091 if (!assembleSensorData(ros::Duration(15.0))) 00092 return false; 00093 ROS_INFO("Assembled Sensor Data"); 00094 00095 if (!priv_nh_.ok()) 00096 return false; 00097 00098 ROS_INFO("RGB-D Kinectassembly has succeeded;"); 00099 response.point_cloud = point_cloud_; 00100 response.image = image_; 00101 response.disparity_image = disparity_image_; 00102 response.camera_info = cam_info_; 00103 response.result = response.SUCCESS; 00104 00105 return true; 00106 } 00107 00108 bool RgdbAssemblerKinect::assembleSensorData( ros::Duration time_out ) 00109 { 00110 ROS_INFO("RGB-D Assembly: waiting for messages..."); 00111 00112 MsgSaver<sensor_msgs::Image> recent_image("/camera/rgb/points_image"); 00113 MsgSaver<stereo_msgs::DisparityImage> recent_disparity_image( 00114 "/camera/depth/disparity"); 00115 MsgSaver<sensor_msgs::CameraInfo> recent_camera_info( 00116 "/camera/depth/camera_info"); 00117 MsgSaver<sensor_msgs::PointCloud2> recent_point_cloud("/camera/rgb/points"); 00118 ros::Time start_time = ros::Time::now(); 00119 00120 while ((!recent_disparity_image.hasMsg() || !recent_image.hasMsg() 00121 || !recent_camera_info.hasMsg() || !recent_point_cloud.hasMsg()) 00122 && priv_nh_.ok()) 00123 { 00124 ros::spinOnce(); 00125 00126 ros::Time current_time = ros::Time::now(); 00127 if (time_out >= ros::Duration(0) && current_time - start_time >= time_out) 00128 { 00129 ROS_ERROR("Timed out while waiting for sensor data."); 00130 return false; 00131 } 00132 ros::Duration(1.0).sleep(); 00133 } 00134 if (!priv_nh_.ok()) 00135 return false; 00136 00137 image_ = *recent_image.getMsg(); 00138 disparity_image_ = *recent_disparity_image.getMsg(); 00139 cam_info_ = *recent_camera_info.getMsg(); 00140 point_cloud_ = *recent_point_cloud.getMsg(); 00141 00142 image_.header = disparity_image_.header; 00143 00144 if ( image_.width != disparity_image_.image.width || image_.height != disparity_image_.image.height ) 00145 { 00146 ROS_ERROR( "Size mismatch between image and disparity image!"); 00147 return false; 00148 } 00149 00150 if ( image_.width != point_cloud_.width || image_.height != point_cloud_.height ) 00151 { 00152 ROS_ERROR( "Size mismatch between image and point cloud!"); 00153 return false; 00154 } 00155 00156 return true; 00157 } 00158 00159 } // namespace rgbd_assembler 00160 00161 int main( int argc, char **argv ) 00162 { 00163 ros::init(argc, argv, "rgbd_assembler_kinect_node"); 00164 rgbd_assembler::RgdbAssemblerKinect node; 00165 ros::spin(); 00166 return 0; 00167 }