point_pose_extractor.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include <ros/ros.h>
00037 #include <rospack/rospack.h>
00038 #include <opencv/highgui.h>
00039 #include <cv_bridge/cv_bridge.h>
00040 #include <opencv/cv.hpp>
00041 #pragma message "Compiling " __FILE__ "..."
00042 #include <posedetection_msgs/Feature0DDetect.h>
00043 #include <posedetection_msgs/ImageFeature0D.h>
00044 #include <posedetection_msgs/ObjectDetection.h>
00045 #include <posedetection_msgs/Object6DPose.h>
00046 #include <geometry_msgs/PoseStamped.h>
00047 #include <geometry_msgs/Pose.h>
00048 #include <geometry_msgs/Quaternion.h>
00049 #include <sensor_msgs/image_encodings.h>
00050 #include <image_transport/image_transport.h>
00051 #include <image_geometry/pinhole_camera_model.h>
00052 #include <tf/tf.h>
00053 #include <boost/shared_ptr.hpp>
00054 #include <boost/foreach.hpp>
00055 #include <boost/filesystem.hpp>
00056 #include <vector>
00057 #include <sstream>
00058 #include <iostream>
00059 #include <dynamic_reconfigure/server.h>
00060 #include <jsk_perception/point_pose_extractorConfig.h>
00061 #include <jsk_perception/SetTemplate.h>
00062 #include <jsk_topic_tools/log_utils.h>
00063 namespace enc = sensor_msgs::image_encodings;
00064 
00065 bool _first_sample_change;
00066 
00067 void features2keypoint (posedetection_msgs::Feature0D features,
00068                         std::vector<cv::KeyPoint>& keypoints,
00069                         cv::Mat& descriptors){
00070   keypoints.resize(features.scales.size());
00071   descriptors.create(features.scales.size(),features.descriptor_dim,CV_32FC1);
00072   std::vector<cv::KeyPoint>::iterator keypoint_it = keypoints.begin();
00073   for ( int i=0; keypoint_it != keypoints.end(); ++keypoint_it, ++i ) {
00074     *keypoint_it = cv::KeyPoint(cv::Point2f(features.positions[i*2+0],
00075                                             features.positions[i*2+1]),
00076                                 features.descriptor_dim, // size
00077                                 features.orientations[i], //angle
00078                                 0, // resonse
00079                                 features.scales[i] // octave
00080                                 );
00081     for (int j = 0; j < features.descriptor_dim; j++){
00082       descriptors.at<float>(i,j) =
00083         features.descriptors[i*features.descriptor_dim+j];
00084     }
00085   }
00086 }
00087 
00088 
00089 class Matching_Template
00090 {
00091 public:
00092   std::string _matching_frame;
00093   cv::Mat _template_img;
00094   std::vector<cv::KeyPoint> _template_keypoints;
00095   cv::Mat _template_descriptors;
00096   int _original_width_size;
00097   int _original_height_size;
00098   double _template_width;       // width of template [m]
00099   double _template_height;      // height of template [m]
00100   tf::Transform _relativepose;
00101   cv::Mat _affine_matrix;
00102   std::string _window_name;
00103   // The maximum allowed reprojection error to treat a point pair as an inlier
00104   double _reprojection_threshold;
00105   // threshold on squared ratio of distances between NN and 2nd NN
00106   double _distanceratio_threshold;
00107   std::vector<cv::Point2d> _correspondances;
00108   cv::Mat _previous_stack_img;
00109 
00110   Matching_Template(){
00111   }
00112   Matching_Template(cv::Mat img,
00113                     std::string matching_frame,
00114                     int original_width_size,
00115                     int original_height_size,
00116                     double template_width,
00117                     double template_height,
00118                     tf::Transform relativepose,
00119                     cv::Mat affine_matrix,
00120                     double reprojection_threshold,
00121                     double distanceratio_threshold,
00122                     std::string window_name,
00123                     bool autosize){
00124 
00125     _template_img = img.clone();
00126     _matching_frame = matching_frame;
00127     _original_width_size = original_width_size;
00128     _original_height_size = original_height_size;
00129     _template_width = template_width;
00130     _template_height = template_height;
00131     _relativepose = relativepose;
00132     _affine_matrix = affine_matrix;
00133     _window_name = window_name;
00134     _reprojection_threshold = reprojection_threshold;
00135     _distanceratio_threshold = distanceratio_threshold;
00136     _template_keypoints.clear();
00137     _correspondances.clear();
00138     //    cv::namedWindow(_window_name, autosize ? CV_WINDOW_AUTOSIZE : 0);
00139   }
00140 
00141 
00142   virtual ~Matching_Template(){
00143     std::cerr << "delete " << _window_name << std::endl;
00144   }
00145 
00146 
00147   std::string get_window_name(){
00148     return _window_name;
00149   }
00150 
00151   std::vector<cv::Point2d>* correspondances(){
00152     return &_correspondances;
00153   }
00154 
00155   bool check_template (){
00156     if (_template_img.empty() && _template_keypoints.size() == 0 &&
00157         _template_descriptors.empty()){
00158       return false;
00159     }
00160     else {
00161       return true;
00162     }
00163   }
00164 
00165 
00166   int set_template(ros::ServiceClient client){
00167     posedetection_msgs::Feature0DDetect srv;
00168 
00169     if ( _template_img.empty()) {
00170       JSK_ROS_ERROR ("template picture is empty.");
00171       return -1;
00172     }
00173     JSK_ROS_INFO_STREAM("read template image and call " << client.getService() << " service");
00174     cv_bridge::CvImage cv_img;
00175     cv_img.image = cv::Mat(_template_img);
00176     cv_img.encoding = std::string("bgr8");
00177     srv.request.image = *(cv_img.toImageMsg());
00178     if (client.call(srv)) {
00179       JSK_ROS_INFO_STREAM("get features with " << srv.response.features.scales.size() << " descriptoins");
00180       features2keypoint (srv.response.features, _template_keypoints, _template_descriptors);
00181 
00182       // inverse affine translation
00183       cv::Mat M_inv;
00184       cv::Mat dst;
00185       cv::invert(_affine_matrix, M_inv);
00186       //      cv::drawKeypoints (tmp, _template_keypoints, dst, cv::Scalar::all(1), cv::DrawMatchesFlags::DRAW_RICH_KEYPOINTS);
00187       //      cv::drawKeypoints (tmp, _template_keypoints, dst);
00188       // cv::warpPerspective(_template_img, dst, M_inv,
00189       //                          cv::Size(_original_width_size, _original_height_size),
00190       //                          CV_INTER_LINEAR, IPL_BORDER_CONSTANT, 0);
00191       for (int i = 0; i < (int)_template_keypoints.size(); i++){
00192         cv::Point2f pt;
00193         cv::Mat pt_mat(cv::Size(1,1), CV_32FC2, &pt);
00194         cv::Mat pt_src_mat(cv::Size(1,1), CV_32FC2, &_template_keypoints.at(i).pt);
00195         cv::perspectiveTransform (pt_src_mat, pt_mat, M_inv);
00196         _template_keypoints.at(i).pt = pt_mat.at<cv::Point2f>(0,0);
00197       }
00198       //      cvSetMouseCallback (_window_name.c_str(), &PointPoseExtractor::cvmousecb, this);
00199       //      _template_img = dst;
00200       return 0;
00201     } else {
00202       JSK_ROS_ERROR("Failed to call service Feature0DDetect");
00203       return 1;
00204     }
00205   }
00206 
00207 
00208   double log_fac( int n )
00209   {
00210     static std::vector<double> slog_table;
00211     int osize = slog_table.size();
00212     if(osize <= n){
00213       slog_table.resize(n+1);
00214       if(osize == 0){
00215         slog_table[0] = -1;
00216         slog_table[1] = log(1.0);
00217         osize = 2;
00218       }
00219       for(int i = osize; i <= n; i++ ){
00220         slog_table[i] = slog_table[i-1] + log(i);
00221       }
00222     }
00223     return slog_table[n];
00224   }
00225 
00226   int min_inlier( int n, int m, double p_badsupp, double p_badxform )
00227   {
00228     double pi, sum;
00229     int i, j;
00230     double lp_badsupp = log( p_badsupp );
00231     double lp_badsupp1 = log( 1.0 - p_badsupp );
00232     for( j = m+1; j <= n; j++ ){
00233       sum = 0;
00234       for( i = j; i <= n; i++ ){
00235         pi = (i-m) * lp_badsupp + (n-i+m) * lp_badsupp1 +
00236           log_fac( n - m ) - log_fac( i - m ) - log_fac( n - i );
00237         sum += exp( pi );
00238       }
00239       if( sum < p_badxform )
00240         break;
00241     }
00242     return j;
00243   }
00244 
00245 
00246   bool estimate_od (ros::ServiceClient client, cv::Mat src_img,
00247                     std::vector<cv::KeyPoint> sourceimg_keypoints,
00248                     image_geometry::PinholeCameraModel pcam,
00249                     double err_thr, cv::Mat &stack_img,
00250                     cv::flann::Index* ft, posedetection_msgs::Object6DPose* o6p){
00251 
00252     if ( _template_keypoints.size()== 0 &&
00253          _template_descriptors.empty() ){
00254       set_template(client);
00255     }
00256     if ( _template_keypoints.size()== 0 &&
00257          _template_descriptors.empty() ) {
00258       JSK_ROS_ERROR ("Template image was not set.");
00259       return false;
00260     }
00261     // stacked image
00262     cv::Size stack_size  = cv::Size(MAX(src_img.cols,_template_img.cols),
00263                                     src_img.rows+_template_img.rows);
00264     stack_img = cv::Mat(stack_size,CV_8UC3);
00265     stack_img = cv::Scalar(0);
00266     cv::Mat stack_img_tmp(stack_img,cv::Rect(0,0,_template_img.cols,_template_img.rows));
00267     cv::add(stack_img_tmp, _template_img, stack_img_tmp);
00268     cv::Mat stack_img_src(stack_img,cv::Rect(0,_template_img.rows,src_img.cols,src_img.rows));
00269     cv::add(stack_img_src, src_img, stack_img_src);
00270     _previous_stack_img = stack_img.clone();
00271 
00272     // matching
00273     cv::Mat m_indices(_template_descriptors.rows, 2, CV_32S);
00274     cv::Mat m_dists(_template_descriptors.rows, 2, CV_32F);
00275     ft->knnSearch(_template_descriptors, m_indices, m_dists, 2, cv::flann::SearchParams(-1) );
00276 
00277     // matched points
00278     std::vector<cv::Point2f> pt1, pt2;
00279     std::vector<int> queryIdxs,trainIdxs;
00280     for ( unsigned int j = 0; j < _template_keypoints.size(); j++ ) {
00281       if ( m_dists.at<float>(j,0) < m_dists.at<float>(j,1) * _distanceratio_threshold) {
00282         queryIdxs.push_back(j);
00283         trainIdxs.push_back(m_indices.at<int>(j,0));
00284       }
00285     }
00286     if ( queryIdxs.size() == 0 ) {
00287       JSK_ROS_WARN_STREAM("could not found matched points with distanceratio(" <<_distanceratio_threshold << ")");
00288     } else {
00289       cv::KeyPoint::convert(_template_keypoints,pt1,queryIdxs);
00290       cv::KeyPoint::convert(sourceimg_keypoints,pt2,trainIdxs);
00291     }
00292 
00293     JSK_ROS_INFO ("Found %d total matches among %d template keypoints", (int)pt2.size(), (int)_template_keypoints.size());
00294 
00295     cv::Mat H;
00296     std::vector<uchar> mask((int)pt2.size());
00297 
00298     if ( pt1.size() > 4 ) {
00299           // ToDO for curve face
00300       H = cv::findHomography(cv::Mat(pt1), cv::Mat(pt2), mask, CV_RANSAC, _reprojection_threshold);
00301     }
00302 
00303     // draw line
00304     for (int j = 0; j < (int)pt1.size(); j++){
00305       cv::Point2f pt, pt_orig;
00306       cv::Mat pt_mat(cv::Size(1,1), CV_32FC2, &pt);
00307       cv::Mat pt_src_mat(cv::Size(1,1), CV_32FC2, &pt1.at(j));
00308       cv::perspectiveTransform (pt_src_mat, pt_mat, _affine_matrix);
00309       pt_orig = pt_mat.at<cv::Point2f>(0,0);
00310       if ( mask.at(j)){
00311         cv::line(stack_img, pt_orig, pt2.at(j)+cv::Point2f(0,_template_img.rows),
00312                  CV_RGB(0,255,0), 1,8,0);
00313       }
00314       else {
00315         cv::line(stack_img, pt_orig, pt2.at(j)+cv::Point2f(0,_template_img.rows),
00316                  CV_RGB(255,0,255), 1,8,0);
00317       }
00318     }
00319     int inlier_sum = 0;
00320     for (int k=0; k < (int)mask.size(); k++){
00321       inlier_sum += (int)mask.at(k);
00322     }
00323 
00324     double text_scale = 1.5;
00325     {
00326       int fontFace = 0, thickness = 0, baseLine;
00327       int x, y;
00328       cv::Size text_size;
00329       std::string text;
00330 
00331       text = "inlier: " + boost::lexical_cast<std::string>((int)inlier_sum) + " / " + boost::lexical_cast<std::string>((int)pt2.size());
00332       text_size = cv::getTextSize(text, fontFace, text_scale, thickness, &baseLine);
00333       x = stack_img.size().width - text_size.width;
00334       y = text_size.height + thickness + 10; // 10pt pading
00335       cv::putText (stack_img, text, cv::Point(x, y),
00336                    fontFace, text_scale, CV_RGB(0, 255, 0),
00337                    thickness, 8, false);
00338 
00339       text = "template: " + boost::lexical_cast<std::string>((int)_template_keypoints.size());
00340       text_size = cv::getTextSize(text, fontFace, text_scale, thickness, &baseLine);
00341       x = stack_img.size().width - text_size.width;
00342       y += text_size.height + thickness + 10; // 10pt pading
00343       cv::putText (stack_img, text, cv::Point(x, y),
00344                    fontFace, text_scale, CV_RGB(0, 255, 0),
00345                    thickness, 8, false);
00346     }
00347 
00348     // draw correspondances
00349     JSK_ROS_INFO("  _correspondances.size: %d", (int)_correspondances.size());
00350     for (int j = 0; j < (int)_correspondances.size(); j++){
00351       cv::circle(stack_img, cv::Point2f(_correspondances.at(j).x, _correspondances.at(j).y + _template_img.size().height),
00352                  8, CV_RGB(255,0,0), -1);
00353     }
00354 
00355     JSK_ROS_INFO("    inlier_sum:%d   min_lier:%d", inlier_sum, min_inlier((int)pt2.size(), 4, 0.10, 0.01));
00356     if ((cv::countNonZero( H ) == 0) || (inlier_sum < min_inlier((int)pt2.size(), 4, 0.10, 0.01))){
00357       JSK_ROS_INFO("    inlier_sum < min_lier return-from estimate-od");
00358       if( _window_name != "" )
00359         cv::imshow(_window_name, stack_img);
00360       return false;
00361     }
00362 
00363     std::string _type;
00364     char chr[20];
00365 
00366     // number of match points
00367     sprintf(chr, "%d", (int)pt2.size());
00368     _type = _matching_frame + "_" + std::string(chr);
00369 
00370     sprintf(chr, "%d", inlier_sum);
00371     _type = _type + "_" + std::string(chr);
00372 
00373     cv::Point2f corners2d[4] = {cv::Point2f(0,0),
00374                                 cv::Point2f(_original_width_size,0),
00375                                 cv::Point2f(_original_width_size,_original_height_size),
00376                                 cv::Point2f(0,_original_height_size)};
00377     cv::Mat corners2d_mat (cv::Size(4, 1), CV_32FC2, corners2d);
00378     cv::Point3f corners3d[4] = {cv::Point3f(0,0,0),
00379                                 cv::Point3f(0,_template_width,0),
00380                                 cv::Point3f(_template_height,_template_width,0),
00381                                 cv::Point3f(_template_height,0,0)};
00382     cv::Mat corners3d_mat (cv::Size(4, 1), CV_32FC3, corners3d);
00383 
00384     cv::Mat corners2d_mat_trans;
00385 
00386     cv::perspectiveTransform (corners2d_mat, corners2d_mat_trans, H);
00387 
00388     double fR3[3], fT3[3];
00389     cv::Mat rvec(3, 1, CV_64FC1, fR3);
00390     cv::Mat tvec(3, 1, CV_64FC1, fT3);
00391     cv::Mat zero_distortion_mat = cv::Mat::zeros(4, 1, CV_64FC1);
00392 
00393     cv::solvePnP (corners3d_mat, corners2d_mat_trans, 
00394                   pcam.intrinsicMatrix(),
00395                   zero_distortion_mat,//if unrectified: pcam.distortionCoeffs()
00396                   rvec, tvec);
00397 
00398     tf::Transform checktf, resulttf;
00399 
00400     checktf.setOrigin( tf::Vector3(fT3[0], fT3[1], fT3[2] ) );
00401 
00402     double rx = fR3[0], ry = fR3[1], rz = fR3[2];
00403     tf::Quaternion quat;
00404     double angle = cv::norm(rvec);
00405     quat.setRotation(tf::Vector3(rx/angle, ry/angle, rz/angle), angle);
00406     checktf.setRotation( quat );
00407 
00408     resulttf = checktf * _relativepose;
00409 
00410     JSK_ROS_INFO( "      tx: (%0.2lf,%0.2lf,%0.2lf) rx: (%0.2lf,%0.2lf,%0.2lf)",
00411               resulttf.getOrigin().getX(),
00412               resulttf.getOrigin().getY(),
00413               resulttf.getOrigin().getZ(),
00414               resulttf.getRotation().getAxis().x() * resulttf.getRotation().getAngle(),
00415               resulttf.getRotation().getAxis().y() * resulttf.getRotation().getAngle(),
00416               resulttf.getRotation().getAxis().z() * resulttf.getRotation().getAngle());
00417 
00418     o6p->pose.position.x = resulttf.getOrigin().getX();
00419     o6p->pose.position.y = resulttf.getOrigin().getY();
00420     o6p->pose.position.z = resulttf.getOrigin().getZ();
00421     o6p->pose.orientation.w = resulttf.getRotation().w();
00422     o6p->pose.orientation.x = resulttf.getRotation().x();
00423     o6p->pose.orientation.y = resulttf.getRotation().y();
00424     o6p->pose.orientation.z = resulttf.getRotation().z();
00425     o6p->type = _matching_frame; // _type
00426 
00427     // draw 3d cube model
00428     std::vector<cv::Point2f> projected_top;
00429     {
00430       tf::Vector3 coords[8] = {tf::Vector3(0,0,0),
00431                                tf::Vector3(0, _template_width, 0),
00432                                tf::Vector3(_template_height, _template_width,0),
00433                                tf::Vector3(_template_height, 0, 0),
00434                                tf::Vector3(0, 0, -0.03),
00435                                tf::Vector3(0, _template_width, -0.03),
00436                                tf::Vector3(_template_height, _template_width, -0.03),
00437                                tf::Vector3(_template_height, 0, -0.03)};
00438 
00439       projected_top = std::vector<cv::Point2f>(8);
00440 
00441       for(int i=0; i<8; i++) {
00442         coords[i] = checktf * coords[i];
00443         cv::Point3f pt(coords[i].getX(), coords[i].getY(), coords[i].getZ());
00444         projected_top[i] = pcam.project3dToPixel(pt);
00445       }
00446     }
00447 
00448     { // check if the matched region does not too big or too small
00449       float max_x, max_y, min_x, min_y;
00450       max_x = max_y = -1e9;
00451       min_x = min_y = 1e9;
00452       for (int j = 0; j < 4; j++){
00453         cv::Point2f pt = corners2d_mat_trans.at<cv::Point2f>(0,j);
00454         max_x = std::max(max_x, pt.x), max_y = std::max(max_y, pt.y);
00455         min_x = std::min(min_x, pt.x), min_y = std::min(min_y, pt.y);
00456       }
00457       if((max_x - min_x) < 30 || (max_y - min_y) < 30 ||
00458          src_img.rows < (max_x - min_x)/2 || src_img.cols < (max_y - min_y)/2){
00459         JSK_ROS_INFO("        matched region is too big or small (2< && <30) width:%d height:%d return-from estimate-od", max_x - min_x, max_y - min_y);
00460         return false;
00461       }
00462     }
00463 
00464     double err_sum = 0;
00465     bool err_success = true;
00466     for (int j = 0; j < 4; j++){
00467       double err = sqrt(pow((corners2d_mat_trans.at<cv::Point2f>(0,j).x - projected_top.at(j).x), 2) +
00468                       pow((corners2d_mat_trans.at<cv::Point2f>(0,j).y - projected_top.at(j).y), 2));
00469       err_sum += err;
00470     }
00471     if (err_sum > err_thr){
00472       JSK_ROS_INFO("          err_sum:%d > err_thr:%d return-from estimate-od", err_sum, err_thr);
00473       err_success = false;
00474     }
00475     // draw lines around the detected object
00476     for (int j = 0; j < corners2d_mat_trans.cols; j++){
00477       cv::Point2f p1(corners2d_mat_trans.at<cv::Point2f>(0,j).x,
00478                      corners2d_mat_trans.at<cv::Point2f>(0,j).y+_template_img.rows);
00479       cv::Point2f p2(corners2d_mat_trans.at<cv::Point2f>(0,(j+1)%corners2d_mat_trans.cols).x,
00480                      corners2d_mat_trans.at<cv::Point2f>(0,(j+1)%corners2d_mat_trans.cols).y+_template_img.rows);
00481       cv::line (stack_img, p1, p2, CV_RGB(255, 0, 0),
00482                 (err_success?4:1), // width
00483                 CV_AA, 0);
00484     }
00485 
00486     // draw 3d cube model
00487     if(projected_top.size() == 8) { // verify, the size is 8
00488       int cnt = 8;
00489       std::vector<cv::Point2f> ps(cnt);
00490       for(int i=0; i<cnt; i++)
00491         ps[i] = cv::Point2f(projected_top[i].x,
00492                             projected_top[i].y+_template_img.rows);
00493 
00494       int draw_width = ( err_success ? 3 : 1);
00495       for(int i=0; i<4; i++) {
00496         cv::line (stack_img, ps[i], ps[(i+1)%4], CV_RGB(0, 0, 255), draw_width, CV_AA, 0);
00497         cv::line (stack_img, ps[i+4], ps[(i+1)%4+4], CV_RGB(0, 0, 255), draw_width, CV_AA, 0);
00498         cv::line (stack_img, ps[i], ps[i+4], CV_RGB(0, 0, 255), draw_width, CV_AA, 0);
00499       }
00500     }
00501 
00502     // draw coords
00503     if ( err_success )
00504     {
00505       tf::Vector3 coords[4] = { tf::Vector3(0,0,0),
00506                                 tf::Vector3(0.05,0,0),
00507                                 tf::Vector3(0,0.05,0),
00508                                 tf::Vector3(0,0,0.05)};
00509       std::vector<cv::Point2f> ps(4);
00510 
00511       for(int i=0; i<4; i++) {
00512         coords[i] = resulttf * coords[i];
00513         cv::Point3f pt(coords[i].getX(), coords[i].getY(), coords[i].getZ());   
00514         ps[i] = pcam.project3dToPixel(pt);
00515         ps[i].y += _template_img.rows; // draw on camera image
00516       }
00517 
00518       cv::line (stack_img, ps[0], ps[1], CV_RGB(255, 0, 0), 3, CV_AA, 0);
00519       cv::line (stack_img, ps[0], ps[2], CV_RGB(0, 255, 0), 3, CV_AA, 0);
00520       cv::line (stack_img, ps[0], ps[3], CV_RGB(0, 0, 255), 3, CV_AA, 0);
00521     }
00522 
00523     // write text on image
00524     {
00525       std::string text;
00526       int x, y;
00527       text = "error: " + boost::lexical_cast<std::string>(err_sum);
00528       x = stack_img.size().width - 16*17*text_scale; // 16pt * 17
00529       y = _template_img.size().height - (16 + 2)*text_scale*6;
00530       cv::putText (stack_img, text, cv::Point(x, y),
00531                    0, text_scale, CV_RGB(0, 255, 0),
00532                    2, 8, false);
00533       JSK_ROS_INFO("      %s < %f (threshold)", text.c_str(), err_thr );
00534     }
00535     // for debug window
00536     if( _window_name != "" )
00537       cv::imshow(_window_name, stack_img);
00538 
00539     return err_success;
00540   }
00541 };  // the end of difinition of class Matching_Template
00542 
00543 
00544 class PointPoseExtractor
00545 {
00546   ros::NodeHandle _n;
00547   image_transport::ImageTransport it;
00548   ros::Subscriber _sub;
00549   ros::ServiceServer _server;
00550   ros::ServiceClient _client;
00551   ros::Publisher _pub, _pub_agg, _pub_pose;
00552   image_transport::Publisher _debug_pub;
00553   double _reprojection_threshold;
00554   double _distanceratio_threshold;
00555   double _th_step;
00556   double _phi_step;
00557   bool _autosize;
00558   double _err_thr;
00559   static std::vector<Matching_Template *> _templates;
00560   image_geometry::PinholeCameraModel pcam;
00561   bool pnod;
00562   bool _initialized;
00563   bool _viewer;
00564 
00565 public:
00566   PointPoseExtractor() : it(ros::NodeHandle("~")) {
00567     // _sub = _n.subscribe("ImageFeature0D", 1,
00568     //                     &PointPoseExtractor::imagefeature_cb, this);
00569     _client = _n.serviceClient<posedetection_msgs::Feature0DDetect>("Feature0DDetect");
00570     _pub = _n.advertise<posedetection_msgs::ObjectDetection>("ObjectDetection", 10);
00571     _pub_agg = _n.advertise<posedetection_msgs::ObjectDetection>("ObjectDetection_agg", 10);
00572     _pub_pose = _n.advertise<geometry_msgs::PoseStamped>("object_pose", 10);
00573     _debug_pub = it.advertise("debug_image", 1);
00574     _server = _n.advertiseService("SetTemplate", &PointPoseExtractor::settemplate_cb, this);
00575     _initialized = false;
00576   }
00577 
00578   virtual ~PointPoseExtractor(){
00579     _sub.shutdown();
00580     _client.shutdown();
00581     _pub.shutdown();
00582     _pub_agg.shutdown();
00583   }
00584 
00585   static void make_template_from_mousecb(Matching_Template *mt){
00586     cv::Mat H;
00587     cv::Mat tmp_template, tmp_warp_template;
00588     std::vector<cv::Point2f>pt1, pt2;
00589     double width, height;
00590     std::string filename;
00591     std::cout << "input template's [width]" << std::endl;
00592     std::cin >> width;
00593     std::cout << "input template's [height]" << std::endl;
00594     std::cin >> height;
00595     std::cout << "input template's [filename]" << std::endl;
00596     std::cin >> filename;
00597 
00598     for (int i = 0; i < 4; i++){
00599       pt1.push_back(cv::Point2d((int)mt->_correspondances.at(i).x,
00600                                 (int)mt->_correspondances.at(i).y + mt->_template_img.size().height));
00601     }
00602     cv::Rect rect = cv::boundingRect(cv::Mat(pt1));
00603     double scale = std::max(width, height) / 500.0;
00604     int iwidth = width / scale, iheight = height / scale;
00605     pt2.push_back(cv::Point2d(0,0));
00606     pt2.push_back(cv::Point2d(iwidth,0));
00607     pt2.push_back(cv::Point2d(iwidth,iheight));
00608     pt2.push_back(cv::Point2d(0,     iheight));
00609     H = cv::findHomography(cv::Mat(pt1), cv::Mat(pt2));
00610 
00611     cv::getRectSubPix(mt->_previous_stack_img, rect.size(),
00612                       cv::Point2f((rect.tl().x + rect.br().x)/2.0,(rect.tl().y + rect.br().y)/2.0),
00613                       tmp_template);
00614     cv::warpPerspective(mt->_previous_stack_img, tmp_warp_template, H, cv::Size(iwidth, iheight));
00615 
00616     try {
00617       cv::imwrite(filename,tmp_template);
00618       boost::filesystem::path fname(filename);
00619       std::stringstream ss;
00620       ss << fname.stem() << "_wrap" << fname.extension();
00621       cv::imwrite(ss.str(),tmp_warp_template);
00622     }catch (cv::Exception e) {
00623       std::cerr << e.what()  << std::endl;
00624     }
00625 
00626     for (int i = 0; i < (int)pt1.size(); i++){
00627       pt2.push_back(cv::Point2d((int)pt1.at(i).x - rect.x,
00628                                 (int)pt1.at(i).y - rect.y - mt->_template_img.size().height));
00629     }
00630     // cv::Mat mask_img = cv::Mat::zeros(tmp_template.size(), CV_8UC3);
00631     // cv::fillConvexPoly(mask_img, pt2.begin(), (int)pt2.size(), CV_RGB(255, 255, 255));
00632 
00633     // cv::namedWindow("hoge", 1);
00634     // cv::imshow("hoge", mask_img);
00635 
00636     cv::Mat M = (cv::Mat_<double>(3,3) << 1,0,0, 0,1,0, 0,0,1);
00637     std::string window_name = "sample" + boost::lexical_cast<std::string>((int)_templates.size());
00638 
00639     Matching_Template* tmplt = 
00640       new Matching_Template (tmp_warp_template, "sample",
00641                              tmp_warp_template.size().width, tmp_warp_template.size().height,
00642                              width, height,
00643                              tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0, 0, 0)),
00644                              M,
00645                              mt->_reprojection_threshold,
00646                              mt->_distanceratio_threshold,
00647                              _first_sample_change ? window_name : mt->_window_name,
00648                              cv::getWindowProperty(mt->_window_name, CV_WND_PROP_AUTOSIZE));
00649 
00650     mt->_correspondances.clear();
00651     _templates.push_back(tmplt);
00652     cv::namedWindow(_first_sample_change ? window_name : mt->_window_name,
00653                     cv::getWindowProperty(mt->_window_name, CV_WND_PROP_AUTOSIZE));
00654     cvSetMouseCallback (_first_sample_change ? window_name.c_str() : mt->_window_name.c_str(),
00655                         &cvmousecb, static_cast<void *>(_templates.back()));
00656     _first_sample_change = true;
00657   }
00658 
00659   static void cvmousecb (int event, int x, int y, int flags, void* param){
00660     Matching_Template *mt = (Matching_Template*)param;
00661     // std::cerr << "mousecb_ -> " << mt << std::endl;
00662     switch (event){
00663     case CV_EVENT_LBUTTONUP: {
00664       cv::Point2d pt(x,y - (int)mt->_template_img.size().height);
00665       JSK_ROS_INFO("add correspondence (%d, %d)", (int)pt.x, (int)pt.y);
00666       mt->_correspondances.push_back(pt);
00667       if ((int)mt->_correspondances.size() >= 4){
00668         make_template_from_mousecb(mt);
00669         mt->_correspondances.clear();
00670         JSK_ROS_INFO("reset");
00671       }
00672       break;
00673     }
00674     case CV_EVENT_RBUTTONUP: {
00675       mt->_correspondances.clear();
00676       JSK_ROS_INFO("reset");
00677       break;
00678     }
00679     }
00680   }
00681 
00682 
00683   void initialize () {
00684     std::string matching_frame;
00685     std::string _pose_str;
00686     double template_width;
00687     double template_height;
00688     std::string template_filename;
00689     std::string window_name;
00690     ros::NodeHandle local_nh("~");
00691 
00692     local_nh.param("child_frame_id", matching_frame, std::string("matching"));
00693     local_nh.param("object_width",  template_width,  0.06);
00694     local_nh.param("object_height", template_height, 0.0739);
00695     local_nh.param("relative_pose", _pose_str, std::string("0 0 0 0 0 0 1"));
00696     std::string default_template_file_name;
00697     try {
00698 #ifdef ROSPACK_EXPORT
00699       rospack::ROSPack rp;
00700       rospack::Package *p = rp.get_pkg("jsk_perception");
00701       if (p!=NULL) default_template_file_name = p->path + std::string("/sample/opencv-logo2.png");
00702 #else
00703       rospack::Rospack rp;
00704       std::vector<std::string> search_path;
00705       rp.getSearchPathFromEnv(search_path);
00706       rp.crawl(search_path, 1);
00707       std::string path;
00708       if (rp.find("jsk_perception",path)==true) default_template_file_name = path + std::string("/sample/opencv-logo2.png");
00709 #endif
00710     } catch (std::runtime_error &e) {
00711     }
00712     local_nh.param("template_filename", template_filename, default_template_file_name);
00713     local_nh.param("reprojection_threshold", _reprojection_threshold, 3.0);
00714     local_nh.param("distanceratio_threshold", _distanceratio_threshold, 0.49);
00715     local_nh.param("error_threshold", _err_thr, 50.0);
00716     local_nh.param("theta_step", _th_step, 5.0);
00717     local_nh.param("phi_step", _phi_step, 5.0);
00718     local_nh.param("viewer_window", _viewer, true);
00719     local_nh.param("window_name", window_name, std::string("sample1"));
00720     local_nh.param("autosize", _autosize, false);
00721     local_nh.param("publish_null_object_detection", pnod, false);
00722 
00723     _first_sample_change = false;
00724 
00725     // make one template
00726     cv::Mat template_img;
00727     template_img = cv::imread (template_filename, 1);
00728     if ( template_img.empty()) {
00729       JSK_ROS_ERROR ("template picture <%s> cannot read. template picture is not found or uses unsuported format.", template_filename.c_str());
00730       return;
00731     }
00732 
00733     // relative pose
00734     std::vector<double> rv(7);
00735     std::istringstream iss(_pose_str);
00736     tf::Transform transform;
00737     for(int i=0; i<6; i++)
00738       iss >> rv[i];
00739 
00740     if (iss.eof()) { // use rpy expression
00741       transform = tf::Transform(tf::createQuaternionFromRPY(rv[3], rv[4], rv[5]),
00742                                  tf::Vector3(rv[0], rv[1], rv[2]));
00743     } else {  // use quaternion expression
00744       iss >> rv[6];
00745       transform = tf::Transform(tf::Quaternion(rv[3], rv[4], rv[5], rv[6]),
00746                                  tf::Vector3(rv[0], rv[1], rv[2]));
00747     }
00748 
00749     // add the image to template list
00750     add_new_template(template_img, window_name, transform,
00751                      template_width, template_height, _th_step, _phi_step);
00752 
00753   } // initialize
00754 
00755 
00756   cv::Mat make_homography(cv::Mat src, cv::Mat rvec, cv::Mat tvec,
00757                           double template_width, double template_height, cv::Size &size){
00758 
00759     cv::Point3f coner[4] = {cv::Point3f(-(template_width/2.0), -(template_height/2.0),0),
00760                             cv::Point3f(template_width/2.0,-(template_height/2.0),0),
00761                             cv::Point3f(template_width/2.0,template_height/2.0,0),
00762                             cv::Point3f(-(template_width/2.0),template_height/2.0,0)};
00763     cv::Mat coner_mat (cv::Size(4, 1), CV_32FC3, coner);
00764     std::vector<cv::Point2f> coner_img_points;
00765 
00766     cv::Mat zero_distortion_mat = cv::Mat::zeros(4, 1, CV_64FC1);
00767     cv::projectPoints(coner_mat, rvec, tvec,
00768                       pcam.intrinsicMatrix(),
00769                       zero_distortion_mat, // pcam.distortionCoeffs(),
00770                       coner_img_points);
00771     float x_min = 10000, x_max = 0;
00772     float y_min = 10000, y_max = 0;
00773     for (int i = 0; i < (int)coner_img_points.size(); i++){
00774       x_min = std::min(x_min, coner_img_points.at(i).x);
00775       x_max = std::max(x_max, coner_img_points.at(i).x);
00776       y_min = std::min(y_min, coner_img_points.at(i).y);
00777       y_max = std::max(y_max, coner_img_points.at(i).y);
00778     }
00779 
00780     std::vector<cv::Point2f> coner_img_points_trans;
00781     for (int i = 0; i < (int)coner_img_points.size(); i++){
00782       cv::Point2f pt_tmp(coner_img_points.at(i).x - x_min,
00783                          coner_img_points.at(i).y - y_min);
00784       coner_img_points_trans.push_back(pt_tmp);
00785     }
00786 
00787     cv::Point2f template_points[4] = {cv::Point2f(0,0),
00788                                       cv::Point2f(src.size().width,0),
00789                                       cv::Point2f(src.size().width,src.size().height),
00790                                       cv::Point2f(0,src.size().height)};
00791     cv::Mat template_points_mat (cv::Size(4, 1), CV_32FC2, template_points);
00792 
00793     size = cv::Size(x_max - x_min, y_max - y_min);
00794     return cv::findHomography(template_points_mat, cv::Mat(coner_img_points_trans), 0, 3);
00795   }
00796 
00797 
00798   int make_warped_images (cv::Mat src, std::vector<cv::Mat> &imgs,
00799                           std::vector<cv:: Mat> &Mvec,
00800                           double template_width, double template_height,
00801                           double th_step, double phi_step){
00802 
00803     std::vector<cv::Size> sizevec;
00804 
00805     for (int i = (int)((-3.14/4.0)/th_step); i*th_step < 3.14/4.0; i++){
00806       for (int j = (int)((-3.14/4.0)/phi_step); j*phi_step < 3.14/4.0; j++){
00807         double fR3[3], fT3[3];
00808         cv::Mat rvec(3, 1, CV_64FC1, fR3);
00809         cv::Mat tvec(3, 1, CV_64FC1, fT3);
00810 
00811         tf::Quaternion quat;
00812         quat.setEuler(0, th_step*i, phi_step*j);
00813         fR3[0] = quat.getAxis().x() * quat.getAngle();
00814         fR3[1] = quat.getAxis().y() * quat.getAngle();
00815         fR3[2] = quat.getAxis().z() * quat.getAngle();
00816         fT3[0] = 0;
00817         fT3[1] = 0;
00818         fT3[2] = 0.5;
00819 
00820         cv::Mat M;
00821         cv::Size size;
00822         M = make_homography(src, rvec, tvec, template_width, template_height, size);
00823         Mvec.push_back(M);
00824         sizevec.push_back(size);
00825       }
00826     }
00827 
00828     for (int i = 0; i < (int)Mvec.size(); i++){
00829       cv::Mat dst;
00830       cv::warpPerspective(src, dst, Mvec.at(i), sizevec.at(i),
00831                           CV_INTER_LINEAR, IPL_BORDER_CONSTANT, 0);
00832       imgs.push_back(dst);
00833     }
00834     return 0;
00835   }
00836 
00837   bool add_new_template(cv::Mat img, std::string typestr, tf::Transform relative_pose,
00838                         double template_width, double template_height,
00839                         double theta_step=5.0, double phi_step=5.0)
00840   {
00841     std::vector<cv::Mat> imgs;
00842     std::vector<cv::Mat> Mvec;
00843     make_warped_images(img, imgs, Mvec,
00844                        template_width, template_height, theta_step, phi_step);
00845 
00846     for (int i = 0; i < (int)imgs.size(); i++){
00847       std::string type = typestr;
00848       if(imgs.size() > 1) {
00849         char chr[20];
00850         sprintf(chr, "%d", i);
00851         type += "_" + std::string(chr);
00852       }
00853 
00854       Matching_Template * tmplt = 
00855         new Matching_Template(imgs.at(i), type,
00856                               img.size().width, img.size().height,
00857                               template_width, template_height,
00858                               relative_pose, Mvec.at(i),
00859                               _reprojection_threshold,
00860                               _distanceratio_threshold,
00861                               (_viewer ? type : ""), _autosize);
00862       _templates.push_back(tmplt);
00863       if( _viewer )
00864         cv::namedWindow(type, _autosize ? CV_WINDOW_AUTOSIZE : 0);
00865       cvSetMouseCallback (type.c_str(), &cvmousecb, static_cast<void *>(_templates.back()));
00866     }
00867     return true;
00868   }
00869 
00870   bool settemplate_cb (jsk_perception::SetTemplate::Request &req,
00871                        jsk_perception::SetTemplate::Response &res){
00872       cv_bridge::CvImagePtr cv_ptr;
00873       cv_ptr = cv_bridge::toCvCopy(req.image, enc::BGR8);
00874       cv::Mat img(cv_ptr->image);
00875 
00876       tf::Transform transform(tf::Quaternion(req.relativepose.orientation.x,
00877                                              req.relativepose.orientation.y,
00878                                              req.relativepose.orientation.z,
00879                                              req.relativepose.orientation.w),
00880                               tf::Vector3(req.relativepose.position.x,
00881                                           req.relativepose.position.y,
00882                                           req.relativepose.position.z));
00883 
00884       // add the image to template list 
00885       add_new_template(img, req.type, transform,
00886                        req.dimx, req.dimy, 1.0, 1.0);
00887       return true;
00888   }
00889 
00890 
00891   void imagefeature_cb (const posedetection_msgs::ImageFeature0DConstPtr& msg){
00892     std::vector<cv::KeyPoint> sourceimg_keypoints;
00893     cv::Mat sourceimg_descriptors;
00894     std::vector<posedetection_msgs::Object6DPose> vo6p;
00895     posedetection_msgs::ObjectDetection od;
00896 
00897     cv_bridge::CvImagePtr cv_ptr;
00898     cv_ptr = cv_bridge::toCvCopy(msg->image, enc::BGR8);
00899     cv::Mat src_img(cv_ptr->image);
00900 
00901     // from ros messages to keypoint and pin hole camera model
00902     features2keypoint (msg->features, sourceimg_keypoints, sourceimg_descriptors);
00903     pcam.fromCameraInfo(msg->info);
00904     if ( cv::countNonZero(pcam.intrinsicMatrix()) == 0 ) {
00905       JSK_ROS_FATAL("intrinsic matrix is zero, your camera info looks invalid");
00906     }
00907     if ( !_initialized ) {
00908       // make template images from camera info
00909       initialize();
00910       std::cerr << "initialize templates done" << std::endl;
00911       _initialized = true;
00912     }
00913 
00914     if ( sourceimg_keypoints.size () < 2 ) {
00915       JSK_ROS_INFO ("The number of keypoints in source image is less than 2");
00916     }
00917     else {
00918       // make KDTree
00919       cv::flann::Index *ft = new cv::flann::Index(sourceimg_descriptors, cv::flann::KDTreeIndexParams(1));
00920 
00921       // matching and detect object
00922       JSK_ROS_INFO("_templates size: %d", (int)_templates.size());
00923       for (int i = 0; i < (int)_templates.size(); i++){
00924         posedetection_msgs::Object6DPose o6p;
00925 
00926         cv::Mat debug_img;
00927         if (_templates.at(i)->estimate_od(_client, src_img, sourceimg_keypoints, pcam, _err_thr, debug_img, ft, &o6p))
00928           vo6p.push_back(o6p);
00929 
00930         // for debug Image topic
00931         cv_bridge::CvImage out_msg;
00932         out_msg.header   = msg->image.header;
00933         out_msg.encoding = "bgr8";
00934         out_msg.image    = debug_img;
00935         _debug_pub.publish(out_msg.toImageMsg());
00936       }
00937       delete ft;
00938       if (((int)vo6p.size() != 0) || pnod) {
00939         od.header.stamp = msg->image.header.stamp;
00940         od.header.frame_id = msg->image.header.frame_id;
00941         od.objects = vo6p;
00942         _pub.publish(od);
00943         _pub_agg.publish(od);
00944         // Publish result as geometry_msgs/PoseStamped. But it can only contain one object
00945         geometry_msgs::PoseStamped pose_msg;
00946         pose_msg.header = od.header;
00947         pose_msg.pose = od.objects[0].pose;
00948         _pub_pose.publish(pose_msg);
00949       }
00950     }
00951     // BOOST_FOREACH(Matching_Template* mt, _templates) {
00952     //   std::cerr << "templates_ -> " << mt << std::endl;
00953     // }
00954     cv::waitKey( 10 );
00955   }
00956 
00957   /* if there are subscribers of the output topic -> do work
00958          else if -> unregister all topics this node subscribing
00959    */
00960   void check_subscribers()
00961   {
00962         if(_pub.getNumSubscribers() == 0 && _initialized) {
00963           if(_sub)
00964                 _sub.shutdown();
00965           static int i = 0;
00966           if ( i++ % 100 == 0 ) {
00967               JSK_ROS_INFO("wait for subscriberes ... %s", _pub.getTopic().c_str());
00968           }
00969         } else {
00970           if(!_sub)
00971                 _sub = _n.subscribe("ImageFeature0D", 1,
00972                                     &PointPoseExtractor::imagefeature_cb, this);
00973         }
00974   }
00975 
00976   /* callback for dynamic reconfigure */
00977   void dyn_conf_callback(jsk_perception::point_pose_extractorConfig &config,
00978                          uint32_t level) {
00979     std::cout << "id = " << config.template_id << std::endl;
00980     std::cout << "lvl = " << level << std::endl;
00981     if((int)_templates.size() <= config.template_id) {
00982       JSK_ROS_WARN("template_id is invalid");
00983       config.template_id = 0;
00984       if(_templates.size() != 0)
00985         config.frame_id = _templates[0]->_matching_frame;
00986     } else {
00987       Matching_Template* tmpl = _templates[config.template_id];
00988       if(config.frame_id == tmpl->_matching_frame) {
00989         JSK_ROS_WARN("update params");
00990         tmpl->_reprojection_threshold = config.reprojection_threshold;
00991         tmpl->_distanceratio_threshold = config.distanceratio_threshold;
00992         _err_thr = config.error_threshold;
00993       } else {
00994         JSK_ROS_WARN("get params");
00995         config.frame_id = tmpl->_matching_frame;
00996         config.reprojection_threshold = tmpl->_reprojection_threshold;
00997         config.distanceratio_threshold = tmpl->_distanceratio_threshold;
00998         config.error_threshold = _err_thr;
00999       }
01000     }
01001   }
01002 
01003 };  // the end of definition of class PointPoseExtractor
01004 
01005 
01006 std::vector<Matching_Template *> PointPoseExtractor::_templates;
01007 
01008 int main (int argc, char **argv){
01009   ros::init (argc, argv, "PointPoseExtractor");
01010 
01011   PointPoseExtractor matcher;
01012 
01013   dynamic_reconfigure::Server<jsk_perception::point_pose_extractorConfig> server;
01014   dynamic_reconfigure::Server<jsk_perception::point_pose_extractorConfig>::CallbackType f;
01015   f = boost::bind(&PointPoseExtractor::dyn_conf_callback, &matcher, _1, _2);
01016   server.setCallback(f);
01017 
01018   ros::Rate r(10); // 10 hz
01019   while(ros::ok()) {
01020         ros::spinOnce();
01021         matcher.check_subscribers();
01022         r.sleep();
01023   }
01024 
01025   return 0;
01026 }


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:36:15