Go to the documentation of this file.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 <ros/console.h>
00038 #include <ros/ros.h>
00039 #include <cv_bridge/cv_bridge.h>
00040 #include <opencv2/imgproc/imgproc.hpp>
00041 #include <opencv2/calib3d/calib3d.hpp>
00042 #include <image_cb_detector/image_cb_detector.h>
00043
00044 using namespace image_cb_detector;
00045 using namespace std;
00046
00047 bool ImageCbDetector::configure(const ConfigGoal& config)
00048 {
00049 config_ = config;
00050 return true;
00051 }
00052
00053 bool ImageCbDetector::detect(const sensor_msgs::ImageConstPtr& ros_image,
00054 calibration_msgs::CalibrationPattern& result)
00055 {
00056 cv::Mat image;
00057 try
00058 {
00059 image = cv_bridge::toCvShare(ros_image, "mono8")->image;
00060 }
00061 catch (cv_bridge::Exception error)
00062 {
00063 ROS_ERROR("error");
00064 return false;
00065 }
00066
00067
00068
00069
00070 const int scaled_width = (int) (.5 + image.cols * config_.width_scaling);
00071 const int scaled_height = (int) (.5 + image.rows * config_.height_scaling);
00072 cv::Mat image_scaled;
00073 cv::resize(image, image_scaled, cv::Size(scaled_width, scaled_height), 0, 0, CV_INTER_LINEAR);
00074
00075
00076 vector<cv::Point2f> cv_corners;
00077 cv_corners.resize(config_.num_x*config_.num_y);
00078
00079
00080 cv::Size board_size(config_.num_x, config_.num_y);
00081 int found = cv::findChessboardCorners( image_scaled, board_size, cv_corners, CV_CALIB_CB_ADAPTIVE_THRESH) ;
00082
00083 if(found)
00084 {
00085 ROS_DEBUG("Found CB");
00086
00087
00088
00089 cv::Size subpixel_window(config_.subpixel_window,
00090 config_.subpixel_window);
00091 cv::Size subpixel_zero_zone(config_.subpixel_zero_zone,
00092 config_.subpixel_zero_zone);
00093
00094
00095 cv::cornerSubPix( image_scaled, cv_corners,
00096 subpixel_window,
00097 subpixel_zero_zone,
00098 cv::TermCriteria(CV_TERMCRIT_ITER,20,1e-2));
00099 }
00100 else
00101 ROS_DEBUG("Didn't find CB");
00102
00103
00104 result.header.stamp = ros_image->header.stamp;
00105 result.header.frame_id = ros_image->header.frame_id;
00106
00107 result.object_points.resize(config_.num_x * config_.num_y);
00108 for (unsigned int i=0; i < config_.num_y; i++)
00109 {
00110 for (unsigned int j=0; j < config_.num_x; j++)
00111 {
00112 result.object_points[i*config_.num_x + j].x = j*config_.spacing_x;
00113 result.object_points[i*config_.num_x + j].y = i*config_.spacing_y;
00114 result.object_points[i*config_.num_x + j].z = 0.0;
00115 }
00116 }
00117
00118 result.image_points.resize(cv_corners.size());
00119
00120 for (size_t i=0; i < cv_corners.size(); i++)
00121 {
00122 result.image_points[i].x = cv_corners[i].x / config_.width_scaling;
00123 result.image_points[i].y = cv_corners[i].y / config_.height_scaling;
00124 }
00125
00126 result.success = found;
00127
00128 return true;
00129 }