$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 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 the Willow Garage 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 00036 00037 #include <laser_cb_detector/laser_cb_detector.h> 00038 #include <ros/console.h> 00039 #include <cv_bridge/CvBridge.h> 00040 //#include <highgui.h> 00041 00042 using namespace std; 00043 using namespace laser_cb_detector; 00044 00045 LaserCbDetector::LaserCbDetector() : configured_(false) 00046 { 00047 00048 } 00049 00050 00051 00052 bool LaserCbDetector::configure(const ConfigGoal& config) 00053 { 00054 config_ = config; 00055 00056 return true; 00057 } 00058 00059 00060 bool LaserCbDetector::detect(const calibration_msgs::DenseLaserSnapshot& snapshot, 00061 calibration_msgs::CalibrationPattern& result) 00062 { 00063 00064 // ***** Convert the snapshot into an image, based on intensity window in config ***** 00065 if(!bridge_.fromIntensity(snapshot, config_.min_intensity, config_.max_intensity)) 00066 return false; 00067 IplImage* image = bridge_.toIpl(); 00068 00069 // ***** Resize the image based on scaling parameters in config ***** 00070 const int scaled_width = (int) (.5 + image->width * config_.width_scaling); 00071 const int scaled_height = (int) (.5 + image->height * config_.height_scaling); 00072 IplImage* image_scaled = cvCreateImage(cvSize( scaled_width, scaled_height), 00073 image->depth, 00074 image->nChannels); 00075 cvResize(image, image_scaled, CV_INTER_LINEAR); 00076 00077 if (config_.flip_horizontal) 00078 { 00079 ROS_DEBUG("Flipping image"); 00080 cvFlip(image_scaled, NULL, 1); 00081 } 00082 else 00083 ROS_DEBUG("Not flipping image"); 00084 00085 //if(!cvSaveImage("/u/vpradeep/scratch/image.png", image)) printf("Could not save\n"); 00086 //if(!cvSaveImage("/u/vpradeep/scratch/image_flipped.png", image_scaled)) printf("Could not save flipped\n"); 00087 00088 // ***** Allocate vector for found corners ***** 00089 vector<CvPoint2D32f> cv_corners; 00090 cv_corners.resize(config_.num_x*config_.num_y); 00091 00092 // ***** Do the actual checkerboard extraction ***** 00093 CvSize board_size = cvSize(config_.num_x, config_.num_y); 00094 int num_corners ; 00095 int found = cvFindChessboardCorners( image_scaled, board_size, &cv_corners[0], &num_corners, 00096 CV_CALIB_CB_ADAPTIVE_THRESH) ; 00097 00098 if(found) 00099 { 00100 ROS_DEBUG("Found checkerboard"); 00101 00102 00103 CvSize subpixel_window = cvSize(config_.subpixel_window, 00104 config_.subpixel_window); 00105 CvSize subpixel_zero_zone = cvSize(config_.subpixel_zero_zone, 00106 config_.subpixel_zero_zone); 00107 00108 // Subpixel fine-tuning stuff 00109 cvFindCornerSubPix(image_scaled, &cv_corners[0], num_corners, 00110 subpixel_window, 00111 subpixel_zero_zone, 00112 cvTermCriteria(CV_TERMCRIT_ITER,20,1e-2)); 00113 } 00114 else 00115 ROS_DEBUG("Did not find checkerboard"); 00116 cvReleaseImage(&image_scaled); 00117 00118 // ***** Downscale the detected corners and generate the CalibrationPattern message ***** 00119 result.header.stamp = snapshot.header.stamp; 00120 result.header.frame_id = snapshot.header.frame_id; 00121 00122 result.object_points.resize(config_.num_x * config_.num_y); 00123 for (unsigned int i=0; i < config_.num_y; i++) 00124 { 00125 for (unsigned int j=0; j < config_.num_x; j++) 00126 { 00127 result.object_points[i*config_.num_x + j].x = j*config_.spacing_x; 00128 result.object_points[i*config_.num_x + j].y = i*config_.spacing_y; 00129 result.object_points[i*config_.num_x + j].z = 0.0; 00130 } 00131 } 00132 00133 result.image_points.resize(num_corners); 00134 00135 for (int i=0; i < num_corners; i++) 00136 { 00137 if (config_.flip_horizontal) 00138 result.image_points[i].x = image->width - (cv_corners[i].x / config_.width_scaling) - 1; 00139 else 00140 result.image_points[i].x = cv_corners[i].x / config_.width_scaling; 00141 result.image_points[i].y = cv_corners[i].y / config_.height_scaling; 00142 } 00143 00144 result.success = found; 00145 00146 return true; 00147 } 00148 00149 bool LaserCbDetector::getImage(const calibration_msgs::DenseLaserSnapshot& snapshot, sensor_msgs::Image& ros_image) 00150 { 00151 if(!bridge_.fromIntensity(snapshot, config_.min_intensity, config_.max_intensity)) 00152 { 00153 ROS_ERROR("Error building IplImage from DenseLaserSnapshot's intensity data"); 00154 return false; 00155 } 00156 IplImage* image = bridge_.toIpl(); 00157 00158 if(!sensor_msgs::CvBridge::fromIpltoRosImage(image, ros_image, "mono8")) 00159 { 00160 ROS_ERROR("Error converting IplImage to a ROS sensor_msgs::Image"); 00161 return false; 00162 } 00163 00164 return true; 00165 }