consensus_tracking.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #include <algorithm>
37 #define _USE_MATH_DEFINES
38 #include <math.h>
39 
40 #include <opencv2/opencv.hpp>
41 
42 #include <cv_bridge/cv_bridge.h>
43 #include <sensor_msgs/Image.h>
45 
47 
48 namespace jsk_perception
49 {
51  {
52  DiagnosticNodelet::onInit();
53 
54  pnh_->param("approximate_sync", approximate_sync_, false);
55  pnh_->param("queue_size", queue_size_, 100);
56 
57  pub_mask_image_ = advertise<sensor_msgs::Image>(*pnh_, "output/mask", 1);
58  pub_debug_image_ = advertise<sensor_msgs::Image>(*pnh_, "debug/image", 1);
59 
60  // subscribers to set initial tracking window.
61  sub_image_to_init_.subscribe(*pnh_, "input", 1);
62  sub_polygon_to_init_.subscribe(*pnh_, "input/polygon", 1);
64  {
65  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
67  async_->registerCallback(boost::bind(&ConsensusTracking::setInitialWindow, this, _1, _2));
68  }
69  else
70  {
71  sync_ = boost::make_shared<message_filters::Synchronizer<ExactSyncPolicy> >(queue_size_);
73  sync_->registerCallback(boost::bind(&ConsensusTracking::setInitialWindow, this, _1, _2));
74  }
75 
77  }
78 
80  {
81  // subscribers to process the tracking
82  sub_image_ = pnh_->subscribe("input", 1, &ConsensusTracking::getTrackingResult, this);
83  }
84 
86  {
88  }
89 
90  void ConsensusTracking::setInitialWindow(const sensor_msgs::Image::ConstPtr& image_msg,
91  const geometry_msgs::PolygonStamped::ConstPtr& poly_msg)
92  {
93  boost::mutex::scoped_lock lock(mutex_);
94 
95  cv::Mat image = cv_bridge::toCvCopy(image_msg, sensor_msgs::image_encodings::BGR8)->image;
96 
97  // Convert color image to gray to track.
98  cv::Mat gray;
99  cv::cvtColor(image, gray, CV_BGR2GRAY);
100 
101  // Set initial rectangle vertices
102  cv::Point2f initial_top_left = cv::Point2f(poly_msg->polygon.points[0].x, poly_msg->polygon.points[0].y);
103  cv::Point2f initial_bottom_right = cv::Point2f(poly_msg->polygon.points[1].x, poly_msg->polygon.points[1].y);
104 
105  cmt.initialise(gray, initial_top_left, initial_bottom_right);
106  window_initialized_ = true;
107  ROS_INFO("A window is initialized. top_left: (%lf, %lf), bottom_right: (%lf, %lf)",
108  initial_top_left.x, initial_top_left.y, initial_bottom_right.x, initial_bottom_right.y);
109  }
110 
111  void ConsensusTracking::getTrackingResult(const sensor_msgs::Image::ConstPtr& image_msg)
112  {
113  boost::mutex::scoped_lock lock(mutex_);
114 
115  if (!window_initialized_)
116  {
117  return;
118  }
119 
120  cv::Mat image = cv_bridge::toCvCopy(image_msg, sensor_msgs::image_encodings::BGR8)->image;
121 
122  // Convert color image to gray and track it.
123  cv::Mat gray;
124  cv::cvtColor(image, gray, CV_BGR2GRAY);
125  cmt.processFrame(gray);
126 
127  // Draw rectangle for debug view.
128  for (int i=0; i < cmt.trackedKeypoints.size(); i++)
129  {
130  cv::circle(image, cmt.trackedKeypoints[i].first.pt, 3, cv::Scalar(255, 0, 0));
131  }
132  cv::line(image, cmt.topLeft, cmt.topRight, cv::Scalar(0, 30, 255));
133  cv::line(image, cmt.topRight, cmt.bottomRight, cv::Scalar(0, 30, 255));
134  cv::line(image, cmt.bottomRight, cmt.bottomLeft, cv::Scalar(0, 30, 255));
135  cv::line(image, cmt.bottomLeft, cmt.topLeft, cv::Scalar(0, 30, 255));
136 
137  // Generate object mask.
138  cv::Point diff = cmt.topLeft - cmt.bottomLeft;
139  cv::Point center2 = cmt.topLeft + cmt.bottomRight;
140  cv::Point2f center = cv::Point2f(center2.x / 2, center2.y / 2);
141  cv::Size2f size = cv::Size2f(cv::norm(cmt.topLeft - cmt.topRight), cv::norm(cmt.topLeft - cmt.bottomLeft));
142  cv::RotatedRect rRect = cv::RotatedRect(center, size, asin(diff.x / cv::norm(diff)) * 180 / M_PI);
143  cv::Point2f vertices2f[4];
144  rRect.points(vertices2f);
145  cv::Point vertices[4];
146  for (int i = 0; i < 4; ++i)
147  {
148  vertices[i] = vertices2f[i];
149  }
150  cv::Mat mask = cv::Mat::zeros(image.rows, image.cols, CV_8UC1);
151  cv::fillConvexPoly(mask, vertices, 4, cv::Scalar(255));
152 
153  // Publish all.
154  pub_mask_image_.publish(cv_bridge::CvImage(image_msg->header,
156  mask).toImageMsg());
157  pub_debug_image_.publish(cv_bridge::CvImage(image_msg->header,
159  image).toImageMsg());
160  }
161 } // namespace jsk_perception
162 
message_filters::Subscriber< sensor_msgs::Image > sub_image_to_init_
void publish(const boost::shared_ptr< M > &message) const
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
PLUGINLIB_EXPORT_CLASS(jsk_perception::ConsensusTracking, nodelet::Nodelet)
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
#define M_PI
#define ROS_INFO(...)
boost::shared_ptr< ros::NodeHandle > pnh_
INLINE Rall1d< T, V, S > asin(const Rall1d< T, V, S > &x)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
mutex_t * lock
void setInitialWindow(const sensor_msgs::Image::ConstPtr &img_msg, const geometry_msgs::PolygonStamped::ConstPtr &poly_msg)
boost::shared_ptr< message_filters::Synchronizer< ExactSyncPolicy > > sync_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
message_filters::Subscriber< geometry_msgs::PolygonStamped > sub_polygon_to_init_
virtual void getTrackingResult(const sensor_msgs::Image::ConstPtr &image_msg)
sensor_msgs::ImagePtr toImageMsg() const


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27