$search
00001 /* 00002 * Software License Agreement (Modified BSD License) 00003 * 00004 * Copyright (c) 2012, PAL Robotics, S.L. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of PAL Robotics, S.L. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 */ 00034 00042 #include <ros/ros.h> 00043 #include <opencv2/core/core.hpp> 00044 #include <opencv2/imgproc/imgproc.hpp> 00045 #include <opencv2/highgui/highgui.hpp> 00046 00047 #include <image_transport/image_transport.h> 00048 #include <cv_bridge/cv_bridge.h> 00049 #include <sensor_msgs/image_encodings.h> 00050 #include <stereo_msgs/DisparityImage.h> 00051 00052 #include <dynamic_reconfigure/server.h> 00053 #include <pal_vision_segmentation/DisparitySegmentConfig.h> 00054 00055 /***Variables used in callbacks***/ 00056 image_transport::Publisher mask_pub; 00057 int threshold; 00058 int dilate_iterations; 00059 int dilate_size; 00060 int erode_iterations; 00061 int erode_size; 00062 int scale_factor; 00063 cv::Mat image_rect; 00064 image_transport::CameraPublisher cam_pub; 00065 sensor_msgs::CameraInfo camera_info; 00066 ros::Subscriber cam_info_sub; 00067 cv::Mat mask; 00068 /***end of callback section***/ 00069 00070 void disparityCb(const stereo_msgs::DisparityImageConstPtr& msg) 00071 { 00072 if(cam_pub.getNumSubscribers() > 0 || 00073 mask_pub.getNumSubscribers() > 0) 00074 { 00075 // double ticksBefore = cv::getTickCount(); 00076 // Check for common errors in input 00077 if (msg->min_disparity == 0.0 && msg->max_disparity == 0.0) 00078 { 00079 ROS_ERROR("Disparity image fields min_disparity and max_disparity are not set"); 00080 return; 00081 } 00082 if (msg->image.encoding != sensor_msgs::image_encodings::TYPE_32FC1) 00083 { 00084 ROS_ERROR("Disparity image must be 32-bit floating point (encoding '32FC1'), but has encoding '%s'", 00085 msg->image.encoding.c_str()); 00086 return; 00087 } 00088 00089 // code taken from image_view / disparity_view 00090 // Colormap and display the disparity image 00091 float min_disparity = msg->min_disparity; 00092 float max_disparity = msg->max_disparity; 00093 float multiplier = 255.0f / (max_disparity - min_disparity); 00094 00095 const cv::Mat_<float> dmat(msg->image.height, msg->image.width, 00096 (float*)&msg->image.data[0], msg->image.step); 00097 cv::Mat disparity_greyscale; 00098 disparity_greyscale.create(msg->image.height, msg->image.width, CV_8UC1); 00099 00100 for (int row = 0; row < disparity_greyscale.rows; ++row) { 00101 const float* d = dmat[row]; 00102 for (int col = 0; col < disparity_greyscale.cols; ++col) { 00103 int index = (d[col] - min_disparity) * multiplier + 0.5; 00104 00105 //index = std::min(255, std::max(0, index)); 00106 // pushing it into the interval does not matter because of the threshold afterwards 00107 if(index >= threshold) 00108 disparity_greyscale.at<uchar>(row, col) = 255; 00109 else 00110 disparity_greyscale.at<uchar>(row, col) = 0; 00111 } 00112 } 00113 00114 cv::Mat tmp1, mask; 00115 cv::erode(disparity_greyscale, tmp1, 00116 cv::Mat::ones(erode_size, erode_size, CV_8UC1), 00117 cv::Point(-1, -1), erode_iterations); 00118 cv::dilate(tmp1, mask, 00119 cv::Mat::ones(dilate_size, dilate_size, CV_8UC1), 00120 cv::Point(-1, -1), dilate_iterations); 00121 00122 if(mask_pub.getNumSubscribers() > 0) 00123 { 00124 cv_bridge::CvImage mask_msg; 00125 mask_msg.header = msg->header; 00126 mask_msg.encoding = sensor_msgs::image_encodings::TYPE_8UC1; 00127 mask_msg.image = mask; 00128 mask_pub.publish(mask_msg.toImageMsg()); 00129 } 00130 00131 if(!image_rect.empty() && cam_pub.getNumSubscribers() > 0) 00132 { 00133 cv::Mat masked; 00134 image_rect.copyTo(masked, mask); 00135 cv_bridge::CvImage masked_msg; 00136 masked_msg.header = msg->header; 00137 masked_msg.encoding = sensor_msgs::image_encodings::BGR8; 00138 00139 //if we want rescale then rescale 00140 if(scale_factor > 1) 00141 { 00142 cv::Mat masked_tmp = masked; 00143 cv::resize(masked_tmp, masked, 00144 cv::Size(masked.cols*scale_factor, masked.rows*scale_factor)); 00145 } 00146 masked_msg.image = masked; 00147 // to provide a synchronized output we publish both topics with the same timestamp 00148 ros::Time currentTime = ros::Time::now(); 00149 masked_msg.header.stamp = currentTime; 00150 camera_info.header.stamp = currentTime; 00151 cam_pub.publish(*masked_msg.toImageMsg(), camera_info); 00152 } 00153 00154 // ROS_INFO("disparityCb runtime: %f ms", 00155 // 1000*(cv::getTickCount() - ticksBefore)/cv::getTickFrequency()); 00156 } 00157 } 00158 00159 void constMaskCb(const stereo_msgs::DisparityImageConstPtr& msg) 00160 { 00161 if(!image_rect.empty()) 00162 { 00163 cv::Mat masked; 00164 image_rect.copyTo(masked, mask); 00165 cv_bridge::CvImage masked_msg; 00166 masked_msg.header = msg->header; 00167 masked_msg.encoding = sensor_msgs::image_encodings::BGR8; 00168 00169 //if we want rescale then rescale 00170 if(scale_factor > 1) 00171 { 00172 cv::Mat masked_tmp = masked; 00173 cv::resize(masked_tmp, masked, 00174 cv::Size(masked.cols*scale_factor, masked.rows*scale_factor)); 00175 } 00176 masked_msg.image = masked; 00177 cam_pub.publish(*masked_msg.toImageMsg(), camera_info); 00178 } 00179 00180 // ROS_INFO("disparityCb runtime: %f ms", 00181 // 1000*(cv::getTickCount() - ticksBefore)/cv::getTickFrequency()); 00182 } 00183 00184 void imageCb(const sensor_msgs::ImageConstPtr& msg) 00185 { 00186 cv_bridge::CvImagePtr cv_ptr; 00187 try 00188 { 00189 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8); 00190 } 00191 catch (cv_bridge::Exception& e) 00192 { 00193 ROS_ERROR("cv_bridge exception: %s", e.what()); 00194 return; 00195 } 00196 00197 image_rect = cv_ptr->image; 00198 } 00199 00200 void reconf_callback(pal_vision_segmentation::DisparitySegmentConfig &config, uint32_t level) 00201 { 00202 threshold = config.threshold; 00203 dilate_iterations = config.dilate_iterations; 00204 dilate_size = config.dilate_size; 00205 erode_iterations = config.erode_iterations; 00206 erode_size = config.erode_size; 00207 } 00208 00209 void camInfoCallback(const sensor_msgs::CameraInfo &msg) 00210 { 00211 camera_info = msg; 00212 // the image is rectified so by default there's no distortion 00213 for(unsigned int i=0; i<camera_info.D.size(); ++i) 00214 camera_info.D[i] = 0.0; 00215 00216 //rescale the parameters if the image is rescaled 00217 if(scale_factor > 1) 00218 { 00219 camera_info.width *= scale_factor; 00220 camera_info.height *= scale_factor; 00221 for(int i=0; i<12; i++) 00222 camera_info.P[i] *= scale_factor; 00223 camera_info.P[10] = 1.0; 00224 } 00225 00226 // Copy the top 3x3 matrix of P into K 00227 for(int i=0; i<3; ++i) 00228 for(int j=0; j<3; ++j) 00229 camera_info.K[i*3+j] = camera_info.P[i*4+j]; 00230 } 00231 00232 int main(int argc, char *argv[] ) 00233 { 00234 ros::init(argc, argv, "disparity_segmentation"); 00235 ros::NodeHandle nh("disparity_segmentation"); 00236 nh.param<int>("threshold", threshold, 89); 00237 nh.param<int>("dilate_iterations", dilate_iterations, 9); 00238 nh.param<int>("dilate_size", dilate_size, 7); 00239 nh.param<int>("erode_iterations", erode_iterations, 1); 00240 nh.param<int>("erode_size", erode_size, 3); 00241 nh.param<int>("scale_factor", scale_factor, 1); 00242 00243 std::string mask_path; 00244 nh.param<std::string>("mask_path", mask_path, ""); 00245 00246 image_transport::ImageTransport it(nh); 00247 ros::Subscriber disp_sub; 00248 if(mask_path == "") 00249 { 00250 disp_sub = nh.subscribe<stereo_msgs::DisparityImage>("/disparity_image", 1, &disparityCb); 00251 } else { 00252 mask = cv::imread(mask_path); 00253 disp_sub = nh.subscribe<stereo_msgs::DisparityImage>("/disparity_image", 1, &constMaskCb); 00254 } 00255 image_transport::Subscriber rect_sub = it.subscribe("/image", 1, &imageCb); 00256 cam_pub = it.advertiseCamera("image_masked", 1); 00257 cam_info_sub = nh.subscribe("/camera_info", 1, &camInfoCallback); 00258 mask_pub = it.advertise("mask", 1); 00259 00260 dynamic_reconfigure::Server<pal_vision_segmentation::DisparitySegmentConfig> server; 00261 dynamic_reconfigure::Server<pal_vision_segmentation::DisparitySegmentConfig>::CallbackType f; 00262 f = boost::bind(&reconf_callback, _1, _2); 00263 server.setCallback(f); 00264 00265 ros::spin(); 00266 } 00267