00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00036
00037 #include <laser_cb_detector/laser_cb_detector.h>
00038 #include <cv_bridge/CvBridge.h>
00039
00040
00041 using namespace std;
00042 using namespace laser_cb_detector;
00043
00044 LaserCbDetector::LaserCbDetector() : configured_(false)
00045 {
00046
00047 }
00048
00049
00050
00051 bool LaserCbDetector::configure(const ConfigGoal& config)
00052 {
00053 config_ = config;
00054
00055 return true;
00056 }
00057
00058
00059 bool LaserCbDetector::detect(const calibration_msgs::DenseLaserSnapshot& snapshot,
00060 calibration_msgs::CalibrationPattern& result)
00061 {
00062
00063
00064 if(!bridge_.fromIntensity(snapshot, config_.min_intensity, config_.max_intensity))
00065 return false;
00066 IplImage* image = bridge_.toIpl();
00067
00068
00069 const int scaled_width = (int) (.5 + image->width * config_.width_scaling);
00070 const int scaled_height = (int) (.5 + image->height * config_.height_scaling);
00071 IplImage* image_scaled = cvCreateImage(cvSize( scaled_width, scaled_height),
00072 image->depth,
00073 image->nChannels);
00074 cvResize(image, image_scaled, CV_INTER_LINEAR);
00075
00076 if (config_.flip_horizontal)
00077 {
00078 ROS_DEBUG("Flipping image");
00079 cvFlip(image_scaled, NULL, 1);
00080 }
00081 else
00082 ROS_DEBUG("Not flipping image");
00083
00084
00085
00086
00087
00088 vector<CvPoint2D32f> cv_corners;
00089 cv_corners.resize(config_.num_x*config_.num_y);
00090
00091
00092 CvSize board_size = cvSize(config_.num_x, config_.num_y);
00093 int num_corners ;
00094 int found = cvFindChessboardCorners( image_scaled, board_size, &cv_corners[0], &num_corners,
00095 CV_CALIB_CB_ADAPTIVE_THRESH) ;
00096
00097 if(found)
00098 {
00099 ROS_DEBUG("Found checkerboard");
00100
00101
00102 CvSize subpixel_window = cvSize(config_.subpixel_window,
00103 config_.subpixel_window);
00104 CvSize subpixel_zero_zone = cvSize(config_.subpixel_zero_zone,
00105 config_.subpixel_zero_zone);
00106
00107
00108 cvFindCornerSubPix(image_scaled, &cv_corners[0], num_corners,
00109 subpixel_window,
00110 subpixel_zero_zone,
00111 cvTermCriteria(CV_TERMCRIT_ITER,20,1e-2));
00112 }
00113 else
00114 ROS_DEBUG("Did not find checkerboard");
00115 cvReleaseImage(&image_scaled);
00116
00117
00118 result.header.stamp = snapshot.header.stamp;
00119 result.header.frame_id = snapshot.header.frame_id;
00120
00121 result.object_points.resize(config_.num_x * config_.num_y);
00122 for (unsigned int i=0; i < config_.num_y; i++)
00123 {
00124 for (unsigned int j=0; j < config_.num_x; j++)
00125 {
00126 result.object_points[i*config_.num_x + j].x = j*config_.spacing_x;
00127 result.object_points[i*config_.num_x + j].y = i*config_.spacing_y;
00128 result.object_points[i*config_.num_x + j].z = 0.0;
00129 }
00130 }
00131
00132 result.image_points.resize(num_corners);
00133
00134 for (int i=0; i < num_corners; i++)
00135 {
00136 if (config_.flip_horizontal)
00137 result.image_points[i].x = image->width - (cv_corners[i].x / config_.width_scaling) - 1;
00138 else
00139 result.image_points[i].x = cv_corners[i].x / config_.width_scaling;
00140 result.image_points[i].y = cv_corners[i].y / config_.height_scaling;
00141 }
00142
00143 result.success = found;
00144
00145 return true;
00146 }
00147
00148 bool LaserCbDetector::getImage(const calibration_msgs::DenseLaserSnapshot& snapshot, sensor_msgs::Image& ros_image)
00149 {
00150 if(!bridge_.fromIntensity(snapshot, config_.min_intensity, config_.max_intensity))
00151 {
00152 ROS_ERROR("Error building IplImage from DenseLaserSnapshot's intensity data");
00153 return false;
00154 }
00155 IplImage* image = bridge_.toIpl();
00156
00157 if(!sensor_msgs::CvBridge::fromIpltoRosImage(image, ros_image, "mono8"))
00158 {
00159 ROS_ERROR("Error converting IplImage to a ROS sensor_msgs::Image");
00160 return false;
00161 }
00162
00163 return true;
00164 }