$search
00001 #include <ros/ros.h> 00002 #include <ros/node_handle.h> 00003 #include <cstdlib> 00004 #include <robot_mask/GetMask.h> 00005 #include <string.h> 00006 #include "cv_bridge/CvBridge.h" 00007 #include <opencv2/highgui/highgui.hpp> 00008 #include <opencv2/core/core.hpp> 00009 #include <boost/thread.hpp> 00010 #include <sensor_msgs/Image.h> 00011 #include <message_filters/subscriber.h> 00012 #include <sensor_msgs/image_encodings.h> 00013 #include <siftfast/siftfast.h> 00014 00015 using namespace message_filters; 00016 using namespace cv::flann; 00017 using namespace cv; 00018 00020 class LatestMatchingTFMessage 00021 { 00022 private: 00023 ros::Subscriber tf_sub_; 00024 ros::Subscriber image_sub_; 00025 std::string source_frame_, camera_frame_; 00026 int fovy_, width_, height_, count_ ; 00027 ros::NodeHandle nh_; 00028 bool valid_, save_images_; 00029 public: 00030 ros::ServiceClient client ; 00031 robot_mask::GetMask srv; 00032 tf::tfMessageConstPtr tf_state , last_matching_tf; 00033 std::string tf_topic_, image_topic_; 00034 sensor_msgs::CvBridge bridge_; 00035 cv::Mat mask_, original_image_ , final_image_ , image_, image_roi_ , image_roi2_; 00036 Rect rect_; 00037 std::string mode_; 00038 double radius_; 00039 int min_nn_ , knn_ ; 00040 00041 LatestMatchingTFMessage(ros::NodeHandle &nh, const std::string &source_frame) 00042 : source_frame_(source_frame), 00043 nh_ (nh), 00044 valid_(false) 00045 { 00046 //subscribe the tf_topic and image_topic 00047 nh_.param("tf_topic", tf_topic_, std::string("/tf")); 00048 nh_.param("image_topic", image_topic_, std::string("/camera/rgb/image_mono")); 00049 tf_sub_ = nh_.subscribe(tf_topic_, 1, &LatestMatchingTFMessage::TFcallback, this); 00050 image_sub_ = nh_.subscribe(image_topic_, 1, &LatestMatchingTFMessage::Imagecallback, this); 00051 00052 //parameters 00053 nh_.param("fovy", fovy_, 25); 00054 nh_.param("width", width_, 640); 00055 nh_.param("height", height_, 480); 00056 nh_.param("camera_frame", camera_frame_, std::string("openni_rgb_optical_frame")); 00057 nh_.param("save_images", save_images_, true); 00058 nh_.param("mode", mode_ , std::string("knn_search")); 00059 nh_.param("min_nn", min_nn_ , 2); 00060 nh_.param("knn", knn_ , 2); 00061 srv.request.width = width_; 00062 srv.request.height = height_; 00063 srv.request.fovy = fovy_; 00064 srv.request.camera_frame = camera_frame_; 00065 count_ = 0; 00066 radius_ = 30; 00067 00068 //instantiate an autogenerated service class, and assign values into its request member. 00069 client = nh.serviceClient<robot_mask::GetMask>("/robot_mask/get_mask"); 00070 //Mat::Mat(int rows, int cols, int type) 00071 mask_.create(srv.request.height, srv.request.width, CV_8UC1); 00072 final_image_.create(srv.request.height, srv.request.width, CV_8UC1); 00073 00074 } 00076 00079 void TFcallback(const tf::tfMessageConstPtr &msg ) 00080 { 00081 for (uint i = 0; i < msg->transforms.size(); i++) 00082 { 00083 //std::cerr << "frame " << i << " " << msg->transforms[i].header.frame_id << std::endl; 00084 if(!valid_) 00085 { 00086 if(msg->transforms[i].header.frame_id == source_frame_) 00087 { 00088 last_matching_tf = msg; 00089 valid_ = true; 00090 } 00091 } 00092 } 00093 } 00094 00096 00104 void Imagecallback(const sensor_msgs::ImageConstPtr& image ) 00105 { 00106 ROS_INFO("[LatestMatchingTFMessage:] Image received in frame: %s with height %d and width %d", 00107 image->header.frame_id.c_str(), image->height, image->width); 00108 if(valid_) 00109 { 00110 srv.request.tf_state = *last_matching_tf; 00111 ROS_INFO("[LatestMatchingTFMessage:] waiting for service server..."); 00112 if(!client.waitForExistence (ros::Duration (1))) 00113 { 00114 ROS_ERROR("[LatestMatchingTFMessage:] Could not find service."); 00115 } 00116 //convert the ros::image in cv::image 00117 try 00118 { 00119 original_image_ = bridge_.imgMsgToCv(image); 00120 ROS_INFO("[LatestMatchingTFMessage:] Image converted"); 00121 } 00122 catch (sensor_msgs::CvBridgeException error) 00123 { 00124 ROS_ERROR("error"); 00125 } 00126 ROS_INFO("[LatestMatchingTFMessage:] The server was found - calling now"); 00127 // calls the service 00128 if (client.call(srv)) 00129 { 00130 //fill the cv:: Mat mask image with the data from srv.response.mask[] 00131 //copy the first 640 elements from mask array into first row of cv::Mat and so on.. 00132 for (unsigned int i=0; i < srv.response.mask.size(); i++) 00133 { 00134 if (srv.response.mask[i] == 1) 00135 mask_.at<uint8_t>(i/mask_.cols, i%mask_.cols) = 0; 00136 else 00137 mask_.at<uint8_t>(i/mask_.cols, i%mask_.cols) = 255; 00138 } 00139 //make the padding around the gripper mask 00140 for (int i=0; i < mask_.rows; i++) 00141 { 00142 for ( int j = 0; j < mask_.cols; j++) 00143 { 00144 if (mask_.at<uint8_t>(i,j-1) == mask_.at<uint8_t>(i,j)) 00145 mask_.at<uint8_t>(i,j-1) = mask_.at<uint8_t>(i,j); 00146 else 00147 { 00148 //increase the mask with 15 pixels 00149 mask_.at<uint8_t>(i,j-1) = 0; 00150 mask_.at<uint8_t>(i,j-2) = 0; 00151 mask_.at<uint8_t>(i,j-3) = 0; 00152 mask_.at<uint8_t>(i,j-4) = 0; 00153 mask_.at<uint8_t>(i,j-5) = 0; 00154 mask_.at<uint8_t>(i,j-6) = 0; 00155 mask_.at<uint8_t>(i,j-7) = 0; 00156 mask_.at<uint8_t>(i,j-8) = 0; 00157 mask_.at<uint8_t>(i,j-9) = 0; 00158 mask_.at<uint8_t>(i,j-10) = 0; 00159 mask_.at<uint8_t>(i,j-11) = 0; 00160 mask_.at<uint8_t>(i,j-12) = 0; 00161 mask_.at<uint8_t>(i,j-13) = 0; 00162 mask_.at<uint8_t>(i,j-14) = 0; 00163 mask_.at<uint8_t>(i,j-15) = 0; 00164 } 00165 } 00166 } 00167 } 00168 else 00169 { 00170 ROS_ERROR("[LatestMatchingTFMessage:] Failed to call service robot_mask"); 00171 valid_ = false; 00172 return; 00173 } 00174 ROS_INFO("after service call"); 00175 //getting the image without the robot hand 00176 final_image_.zeros(srv.request.height, srv.request.width, CV_8UC1); 00177 //--Calculates per-element bit-wise conjunction of two arrays in a final one 00178 bitwise_and(original_image_, mask_, final_image_); 00179 valid_ = false ; 00180 } 00181 else 00182 { 00183 valid_ = false; 00184 return; 00185 } 00186 if(mode_ == "manual") 00187 { 00188 Keypoint template_keypoints = extract_keypoints(final_image_ ,true); 00189 Keypoint template_keypoints1 = template_keypoints; 00190 //the coordinates for the rect if we know the top left point(262,133) and bottom right point(388,400)of box 00191 rect_.x = 262; 00192 rect_.y = 133; 00193 rect_.width = 126; 00194 rect_.height = 267; 00195 00196 image_roi_ = extract_roi(final_image_, template_keypoints, rect_); 00197 visualize(final_image_ , template_keypoints1); 00198 00199 cv::namedWindow("Original Image", CV_WINDOW_AUTOSIZE); 00200 cv::namedWindow("Mask", CV_WINDOW_AUTOSIZE); 00201 cv::namedWindow("Mask Image", CV_WINDOW_AUTOSIZE); 00202 cv::namedWindow("Keypoints Image", CV_WINDOW_AUTOSIZE); 00203 cv::namedWindow("Rect Image", CV_WINDOW_NORMAL); 00204 00205 /* //display windows on the screen 00206 cv::imshow("Original Image", original_image_); 00207 cv::imshow("Mask", mask_); 00208 cv::imshow("Mask Image", final_image_); 00209 cv::imshow("Keypoints Image", image_); 00210 cv::imshow("Rect Image", image_roi_); 00211 cv::waitKey(20);*/ 00212 00213 //save the images 00214 if (save_images_) 00215 { 00216 count_++; 00217 std::stringstream ss; 00218 ss << count_; 00219 cv::imwrite(ss.str() + ".png", original_image_); 00220 cv::imwrite(ss.str() + "a.png", final_image_ ); 00221 cv::imwrite(ss.str() + "b.png", image_roi_); 00222 cv::imwrite(ss.str() + "c.png", image_ ); 00223 } 00224 } 00225 else if(mode_ == "radius_search") 00226 { 00227 cv::Mat query , indices , dists, output_image; 00228 query.create(0, 2, CV_32FC1); 00229 Keypoint template_keypoints2 = extract_keypoints(final_image_ , true); 00230 00231 //copy all the keypoints in a temporary matrix(q) and then push in them in query matrix 00232 int query_rows = 0; 00233 for (int k=0; template_keypoints2 != NULL; ++k, template_keypoints2 = template_keypoints2->next) 00234 { 00235 cv::Mat q(1, 2, CV_32FC1); 00236 q.at<float>(0, 0) = template_keypoints2->col; 00237 q.at<float>(0, 1) = template_keypoints2->row; 00238 query.push_back(q); 00239 query_rows = k; 00240 } 00241 //printing all the elements of query matrix 00242 /*ROS_INFO("query: %d %d ", query.rows, query.cols); 00243 for (int i = 0; i < query.rows; i++) 00244 { 00245 std::cerr << "query:"; 00246 for (int j = 0; j < query.cols; j++) 00247 { 00248 std::cerr << query.at<float>(i, j) << " "; 00249 } 00250 std::cerr << std::endl; 00251 } 00252 std::cerr << "end query" << std::endl; 00253 return;*/ 00254 00255 //resize query and indices matrix to actual sizes of template_keypoints (1 keypoint can has k-1 neighbors) 00256 indices.create(0, query_rows, CV_32SC1); 00257 dists.create(0, query_rows, CV_32FC1); 00258 ROS_INFO("indices: %d %d ", indices.rows, indices.cols); 00259 00260 //search for neighbors 00261 radiusSearch(query, indices, dists, radius_); 00262 00263 cv::Mat min_indices(0, indices.cols, CV_32SC1); 00264 //the inliers vector contains the index rows associated with the query matrix 00265 std::vector<int> inliers; 00266 //copy in min_indices all the keypoints from the indices matrix that have less than min_nn neighbors 00267 00268 //prepare inliers for radiusSearch function 00269 for (int i = 0; i < indices.rows; i++) 00270 { 00271 //check if the indices have min_nn neighbors 00272 if (indices.at<int>(i, min_nn_) != 0) 00273 { 00274 continue; 00275 } 00276 else 00277 { 00278 inliers.push_back(i); 00279 } 00280 } 00281 00282 ROS_INFO("image_final %d, %d", final_image_.rows, final_image_.cols); 00283 output_image.create(final_image_.rows , final_image_.cols, CV_8UC3); 00284 00285 // cvtColor -Converts image from one color space to another 00286 cvtColor(final_image_, output_image, CV_GRAY2RGB ); 00287 00288 image_roi2_ = extract_roi(inliers, query, output_image); 00289 visualize(inliers, query, output_image); 00290 00291 /*// display windows on the screen 00292 cv::imshow("Outliers_removed_Image", output_image); 00293 cv::imshow("Region_of_Interest_Image", image_roi2_); 00294 waitKey(5); 00295 * */ 00296 00297 //save the images 00298 if (save_images_) 00299 { 00300 count_++; 00301 std::stringstream ss; 00302 ss << count_; 00303 cv::imwrite(ss.str() + ".png", output_image); 00304 cv::imwrite(ss.str() + "a.png", image_roi2_); 00305 } 00306 } 00307 else if(mode_ == "knn_search") 00308 { 00309 cv::Mat query , indices , dists, output_image; 00310 query.create(0, 2, CV_32FC1); 00311 Keypoint template_keypoints2 = extract_keypoints(final_image_ , true); 00312 00313 //copy all the keypoints in a temporary matrix(q) and then push in them in query matrix 00314 int query_rows = 0; 00315 for (int k=0; template_keypoints2 != NULL; ++k, template_keypoints2 = template_keypoints2->next) 00316 { 00317 cv::Mat q(1, 2, CV_32FC1); 00318 q.at<float>(0, 0) = template_keypoints2->col; 00319 q.at<float>(0, 1) = template_keypoints2->row; 00320 query.push_back(q); 00321 //query_rows is the total number of features 00322 query_rows = k; 00323 } 00324 //printing all the elements of query matrix 00325 ROS_INFO("query: %d %d ", query.rows, query.cols); 00326 00327 indices.create(0, query_rows, CV_32SC1); 00328 dists.create(0, query_rows, CV_32FC1); 00329 ROS_INFO("indices: %d %d ", indices.rows, indices.cols); 00330 00331 //search for neighbors 00332 knnSearch(query, indices, dists, min_nn_); 00333 00334 // cv::Mat min_indices(0, indices.cols, CV_32SC1); 00335 //the inliers vector contains the index rows associated with the query matrix 00336 std::vector<int> inliers; 00337 //copy in min_indices all the keypoints from the indices matrix that have more than knn_ neighbors 00338 00339 //prepare inliers for knnSearch function 00340 for (int i = 0; i < dists.rows; i++) 00341 { 00342 bool has_outliers = false; 00343 for (int j = 0; j < dists.cols; j++) 00344 { 00345 //check if there is any neighbor outside of radius_ 00346 if (dists.at<float>(i,j) != 0 && dists.at<float>(i,j) > radius_) 00347 { 00348 has_outliers = true; 00349 } 00350 } 00351 if (!has_outliers) 00352 inliers.push_back(i); 00353 has_outliers = false; 00354 } 00355 00356 ROS_INFO("image_final %d, %d", final_image_.rows, final_image_.cols); 00357 00358 output_image.create(final_image_.rows , final_image_.cols, CV_8UC3); 00359 cvtColor(final_image_, output_image, CV_GRAY2RGB ); 00360 00361 image_roi2_ = extract_roi(inliers, query, output_image); 00362 visualize(inliers, query, output_image); 00363 00364 /* //display windows on the screen 00365 cv::imshow("Outliers_removed_Image", output_image); 00366 cv::imshow("Region_of_Interest_Image", image_roi2_); 00367 waitKey(5); 00368 */ 00369 00370 //save the images 00371 if (save_images_) 00372 { 00373 count_++; 00374 std::stringstream ss; 00375 ss << count_; 00376 cv::imwrite(ss.str() + ".png", output_image); 00377 cv::imwrite(ss.str() + "a.png", image_roi2_); 00378 } 00379 } 00380 else 00381 return; 00382 } 00384 00390 void radiusSearch(Mat& query, Mat& indices, Mat& dists, double radius) 00391 { 00392 //index is for accessing the coordinates of keypoints from the query matrix 00393 Index* index; 00394 //populate index tree 00395 // When passing an object of LinearIndexParams type, the index will perform a linear, brute-force search. 00396 index = new Index (query, LinearIndexParams() ); 00397 // radiusSearch can only search one feature at a time for range search 00398 for( int i = 0; i < query.rows; i++ ) 00399 { 00400 //ptr is a pointer for specify the right row for these matrix 00401 Mat q(1, query.cols, CV_32FC1, query.ptr<float>(i) ); 00402 Mat in; 00403 in = Mat::zeros(1, indices.cols, CV_32SC1); 00404 Mat di; 00405 di = Mat::zeros(1, dists.cols,CV_32FC1); 00406 //radius is the maximum distance to the nearest neighbors 00407 index->radiusSearch( q, in, di, radius_ , SearchParams() ); 00408 indices.push_back(in); 00409 dists.push_back(di); 00410 } 00411 //delete the allocated memory for index 00412 delete index; 00413 } 00414 00416 00422 void knnSearch(Mat& query, Mat& indices, Mat& dists, int knn) 00423 { 00424 Index* index; 00425 index = new Index (query, LinearIndexParams() ); 00426 for( int i = 0; i < query.rows; i++ ) 00427 { 00428 Mat q(1, query.cols, CV_32FC1, query.ptr<float>(i) ); 00429 Mat in; 00430 in = Mat::zeros(1, indices.cols, CV_32SC1); 00431 Mat di; 00432 di = Mat::zeros(1, dists.cols,CV_32FC1); 00433 index->knnSearch( q, in, di, knn, SearchParams() ); 00434 indices.push_back(in); 00435 dists.push_back(di); 00436 } 00437 delete index; 00438 } 00439 00441 00445 Keypoint extract_keypoints(cv::Mat & image, bool frames_only) 00446 { 00447 // ROS_INFO("IMAGE %d %d", image.rows , image.cols); 00448 Image sift_image = CreateImage(image.rows, image.cols); 00449 00450 for (int i = 0; i < image.rows; ++i) 00451 { 00452 //copy images from cv:Mat to Image 00453 // int stride -- how many floats until the next row 00454 // (used to add padding to make rows aligned to 16 bytes) 00455 float* pDst = sift_image->pixels + i * sift_image->stride; 00456 for (int j = 0; j < image.cols; ++j) 00457 pDst[j] = image.at<uint8_t>(i, j) * (1.0f / 255.0f); 00458 } 00459 Keypoint keypoints; 00460 if (frames_only) 00461 keypoints = GetKeypointFrames(sift_image); 00462 else 00463 keypoints = GetKeypoints(sift_image); 00464 DestroyAllImages(); 00465 return keypoints; 00466 } 00467 00469 00475 cv::Mat extract_roi(cv::Mat& image, Keypoint &camera_keypoints, Rect rect ) 00476 { 00477 std::vector<Point2f> keypoints_rect; 00478 for (int ii = 0; camera_keypoints != NULL; ++ii, camera_keypoints = camera_keypoints->next) 00479 { 00480 if ((camera_keypoints->col > rect.x) && 00481 (camera_keypoints->col < (rect.x + rect.width)) && 00482 (camera_keypoints->row > rect.y) && 00483 (camera_keypoints->row < (rect.y + rect.height))) 00484 { 00485 Point2f pt; 00486 pt.x = camera_keypoints->col; 00487 pt.y = camera_keypoints->row; 00488 keypoints_rect.push_back(pt); 00489 } 00490 } 00491 // ROS_INFO("GET THE KEYPOINTS %ld ", keypoints_rect.size()); 00492 Rect rect1 = boundingRect(Mat(keypoints_rect)); 00493 // ROS_INFO_STREAM("rect1: " << rect1.x << " " << rect1.y << " " << rect1.width << " " << rect1.height); 00494 Mat image_roi = image(rect1); 00495 return image_roi; 00496 } 00497 00499 00504 cv::Mat extract_roi(std::vector<int> inliers, cv::Mat query, cv::Mat &output_image ) 00505 { 00506 cv::Mat image; 00507 std::vector<Point2f> keypoints_rect; 00508 for (uint ii=0; ii < inliers.size() ; ++ii) 00509 { 00510 Point2f pt; 00511 pt.x = query.at<float>(inliers.at(ii),0); 00512 pt.y = query.at<float>(inliers.at(ii),1); 00513 keypoints_rect.push_back(pt); 00514 } 00515 ROS_INFO("GET THE KEYPOINTS %ld ", keypoints_rect.size()); 00516 00517 if (keypoints_rect.size()!= 0) 00518 { 00519 Rect rect1 = boundingRect(Mat(keypoints_rect)); 00520 ROS_INFO_STREAM("rect1: " << rect1.x << " " << rect1.y << " " << rect1.width << " " << rect1.height); 00521 00522 cv::Mat image_roi2 = output_image(rect1); 00523 return image_roi2; 00524 } 00525 else return image; //an empty region 00526 } 00527 00529 00533 void visualize(cv::Mat camera_image_in, Keypoint &camera_keypoints) 00534 { 00535 image_.create(camera_image_in.cols, camera_image_in.rows, CV_8UC1); 00536 // cvtColor -Converts image from one color space to another 00537 cvtColor(camera_image_in, image_, CV_GRAY2RGB); 00538 // display camera image keypoints 00539 for (int ii=0; camera_keypoints != NULL; ++ii, camera_keypoints = camera_keypoints->next) 00540 { 00541 circle(image_, cvPoint((int) (camera_keypoints->col), (int) (camera_keypoints->row)), 3, 00542 cvScalar(255, 0, 0)); 00543 } 00544 } 00545 00547 00552 void visualize(std::vector<int> inliers, cv::Mat query, cv::Mat &output_image ) 00553 { 00554 // display camera image keypoints 00555 for (uint ii=0; ii < inliers.size() ; ++ii) 00556 { 00557 //the inliers vector contains the rows associated with the query matrix 00558 //the 0 and 1 are the coloums from the query matrix with template1_keypoints 00559 circle(output_image, cvPoint((int) (query.at<float>(inliers.at(ii),0)), (int) (query.at<float>(inliers.at(ii),1))), 3, 00560 cvScalar(255, 0, 0)); 00561 } 00562 } 00563 }; 00564 00566 int main(int argc, char **argv) 00567 { 00568 //get_mask_client - the node name for client , get_mask - node for the server 00569 ros::init(argc, argv, "get_mask_client"); 00570 ros::NodeHandle n("~"); 00571 LatestMatchingTFMessage tf(n, "/base_footprint"); 00572 //enters a loop, calling message callbacks as fast as possible 00573 ros::spin(); 00574 } 00575