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
00035
00036 #include <algorithm>
00037 #define _USE_MATH_DEFINES
00038 #include <math.h>
00039
00040 #include <opencv2/opencv.hpp>
00041
00042 #include <cv_bridge/cv_bridge.h>
00043 #include <sensor_msgs/Image.h>
00044 #include <sensor_msgs/image_encodings.h>
00045
00046 #include "jsk_perception/consensus_tracking.h"
00047
00048 namespace jsk_perception
00049 {
00050 void ConsensusTracking::onInit()
00051 {
00052 DiagnosticNodelet::onInit();
00053
00054 pnh_->param("approximate_sync", approximate_sync_, false);
00055 pnh_->param("queue_size", queue_size_, 100);
00056
00057 pub_mask_image_ = advertise<sensor_msgs::Image>(*pnh_, "output/mask", 1);
00058 pub_debug_image_ = advertise<sensor_msgs::Image>(*pnh_, "debug/image", 1);
00059
00060
00061 sub_image_to_init_.subscribe(*pnh_, "input", 1);
00062 sub_polygon_to_init_.subscribe(*pnh_, "input/polygon", 1);
00063 if (approximate_sync_)
00064 {
00065 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
00066 async_->connectInput(sub_image_to_init_, sub_polygon_to_init_);
00067 async_->registerCallback(boost::bind(&ConsensusTracking::setInitialWindow, this, _1, _2));
00068 }
00069 else
00070 {
00071 sync_ = boost::make_shared<message_filters::Synchronizer<ExactSyncPolicy> >(queue_size_);
00072 sync_->connectInput(sub_image_to_init_, sub_polygon_to_init_);
00073 sync_->registerCallback(boost::bind(&ConsensusTracking::setInitialWindow, this, _1, _2));
00074 }
00075
00076 onInitPostProcess();
00077 }
00078
00079 void ConsensusTracking::subscribe()
00080 {
00081
00082 sub_image_ = pnh_->subscribe("input", 1, &ConsensusTracking::getTrackingResult, this);
00083 }
00084
00085 void ConsensusTracking::unsubscribe()
00086 {
00087 sub_image_.shutdown();
00088 }
00089
00090 void ConsensusTracking::setInitialWindow(const sensor_msgs::Image::ConstPtr& image_msg,
00091 const geometry_msgs::PolygonStamped::ConstPtr& poly_msg)
00092 {
00093 boost::mutex::scoped_lock lock(mutex_);
00094
00095 cv::Mat image = cv_bridge::toCvCopy(image_msg, sensor_msgs::image_encodings::BGR8)->image;
00096
00097
00098 cv::Mat gray;
00099 cv::cvtColor(image, gray, CV_BGR2GRAY);
00100
00101
00102 cv::Point2f initial_top_left = cv::Point2f(poly_msg->polygon.points[0].x, poly_msg->polygon.points[0].y);
00103 cv::Point2f initial_bottom_right = cv::Point2f(poly_msg->polygon.points[1].x, poly_msg->polygon.points[1].y);
00104
00105 cmt.initialise(gray, initial_top_left, initial_bottom_right);
00106 window_initialized_ = true;
00107 ROS_INFO("A window is initialized. top_left: (%lf, %lf), bottom_right: (%lf, %lf)",
00108 initial_top_left.x, initial_top_left.y, initial_bottom_right.x, initial_bottom_right.y);
00109 }
00110
00111 void ConsensusTracking::getTrackingResult(const sensor_msgs::Image::ConstPtr& image_msg)
00112 {
00113 boost::mutex::scoped_lock lock(mutex_);
00114
00115 if (!window_initialized_)
00116 {
00117 return;
00118 }
00119
00120 cv::Mat image = cv_bridge::toCvCopy(image_msg, sensor_msgs::image_encodings::BGR8)->image;
00121
00122
00123 cv::Mat gray;
00124 cv::cvtColor(image, gray, CV_BGR2GRAY);
00125 cmt.processFrame(gray);
00126
00127
00128 for (int i=0; i < cmt.trackedKeypoints.size(); i++)
00129 {
00130 cv::circle(image, cmt.trackedKeypoints[i].first.pt, 3, cv::Scalar(255, 0, 0));
00131 }
00132 cv::line(image, cmt.topLeft, cmt.topRight, cv::Scalar(0, 30, 255));
00133 cv::line(image, cmt.topRight, cmt.bottomRight, cv::Scalar(0, 30, 255));
00134 cv::line(image, cmt.bottomRight, cmt.bottomLeft, cv::Scalar(0, 30, 255));
00135 cv::line(image, cmt.bottomLeft, cmt.topLeft, cv::Scalar(0, 30, 255));
00136
00137
00138 cv::Point diff = cmt.topLeft - cmt.bottomLeft;
00139 cv::Point center2 = cmt.topLeft + cmt.bottomRight;
00140 cv::Point2f center = cv::Point2f(center2.x / 2, center2.y / 2);
00141 cv::Size2f size = cv::Size2f(cv::norm(cmt.topLeft - cmt.topRight), cv::norm(cmt.topLeft - cmt.bottomLeft));
00142 cv::RotatedRect rRect = cv::RotatedRect(center, size, asin(diff.x / cv::norm(diff)) * 180 / M_PI);
00143 cv::Point2f vertices2f[4];
00144 rRect.points(vertices2f);
00145 cv::Point vertices[4];
00146 for (int i = 0; i < 4; ++i)
00147 {
00148 vertices[i] = vertices2f[i];
00149 }
00150 cv::Mat mask = cv::Mat::zeros(image.rows, image.cols, CV_8UC1);
00151 cv::fillConvexPoly(mask, vertices, 4, cv::Scalar(255));
00152
00153
00154 pub_mask_image_.publish(cv_bridge::CvImage(image_msg->header,
00155 sensor_msgs::image_encodings::MONO8,
00156 mask).toImageMsg());
00157 pub_debug_image_.publish(cv_bridge::CvImage(image_msg->header,
00158 sensor_msgs::image_encodings::BGR8,
00159 image).toImageMsg());
00160 }
00161 }
00162
00163 #include <pluginlib/class_list_macros.h>
00164 PLUGINLIB_EXPORT_CLASS(jsk_perception::ConsensusTracking, nodelet::Nodelet);