37 #define _USE_MATH_DEFINES 40 #include <opencv2/opencv.hpp> 43 #include <sensor_msgs/Image.h> 52 DiagnosticNodelet::onInit();
65 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(
queue_size_);
71 sync_ = boost::make_shared<message_filters::Synchronizer<ExactSyncPolicy> >(
queue_size_);
91 const geometry_msgs::PolygonStamped::ConstPtr& poly_msg)
99 cv::cvtColor(image, gray, CV_BGR2GRAY);
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);
105 cmt.initialise(gray, initial_top_left, initial_bottom_right);
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);
124 cv::cvtColor(image, gray, CV_BGR2GRAY);
125 cmt.processFrame(gray);
128 for (
int i=0; i <
cmt.trackedKeypoints.size(); i++)
130 cv::circle(image,
cmt.trackedKeypoints[i].first.pt, 3, cv::Scalar(255, 0, 0));
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));
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)
148 vertices[i] = vertices2f[i];
150 cv::Mat mask = cv::Mat::zeros(image.rows, image.cols, CV_8UC1);
151 cv::fillConvexPoly(mask, vertices, 4, cv::Scalar(255));
message_filters::Subscriber< sensor_msgs::Image > sub_image_to_init_
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher pub_mask_image_
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_
ros::Publisher pub_debug_image_
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())
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_
ros::Subscriber sub_image_
virtual void getTrackingResult(const sensor_msgs::Image::ConstPtr &image_msg)
virtual void unsubscribe()
sensor_msgs::ImagePtr toImageMsg() const