imagesift.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, 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 
37 #ifndef IMAGESIFT_SIFT_NODE_H_
38 #define IMAGESIFT_SIFT_NODE_H_
39 
41 #include <ros/node_handle.h>
42 #include <sensor_msgs/Image.h>
43 #include <posedetection_msgs/ImageFeature0D.h>
44 #include <posedetection_msgs/Feature0DDetect.h>
47 
48 #include <boost/shared_ptr.hpp>
49 #include <boost/thread/mutex.hpp>
50 
51 #include <cv_bridge/cv_bridge.h>
52 #include <siftfast/siftfast.h>
53 
57 
58 namespace imagesift
59 {
61  {
62  public:
64  sensor_msgs::Image,
65  sensor_msgs::Image > SyncPolicy;
67  SiftNode(): DiagnosticNodelet("SiftNode") {}
68  protected:
70  bool _useMask;
71  boost::mutex _mutex;
75  // for useMask
83  posedetection_msgs::ImageFeature0D _sift_msg;
84 
85  virtual void onInit();
86  virtual void subscribe();
87  virtual void unsubscribe();
88  void infoCb(const sensor_msgs::CameraInfoConstPtr& msg_ptr);
89  bool detectCb(posedetection_msgs::Feature0DDetect::Request& req,
90  posedetection_msgs::Feature0DDetect::Response& res);
91  bool detect(posedetection_msgs::Feature0D& features,
92  const sensor_msgs::Image& imagemsg,
93  const sensor_msgs::Image::ConstPtr& mask_ptr);
94  void imageCb(const sensor_msgs::ImageConstPtr& msg_ptr,
95  const sensor_msgs::ImageConstPtr& mask_ptr);
96  void imageCb(const sensor_msgs::ImageConstPtr& msg_ptr);
97  private:
98  };
99 }
100 
101 #endif
message_filters::Subscriber< sensor_msgs::Image > _subMask
Definition: imagesift.h:77
void infoCb(const sensor_msgs::CameraInfoConstPtr &msg_ptr)
Definition: imagesift.cpp:101
ros::ServiceServer _srvDetect
Definition: imagesift.h:79
posedetection_msgs::ImageFeature0D _sift_msg
Definition: imagesift.h:83
ros::Publisher _pubFeatures
Definition: imagesift.h:81
message_filters::Subscriber< sensor_msgs::Image > _subImageWithMask
Definition: imagesift.h:76
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > _sync
Definition: imagesift.h:78
virtual void onInit()
Definition: imagesift.cpp:53
bool detectCb(posedetection_msgs::Feature0DDetect::Request &req, posedetection_msgs::Feature0DDetect::Response &res)
Definition: imagesift.cpp:108
ros::WallTime lasttime
Definition: imagesift.h:66
DiagnosticNodelet(const std::string &name)
image_transport::TransportHints _hints
Definition: imagesift.h:73
ros::Publisher _pubSift
Definition: imagesift.h:82
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicy
Definition: imagesift.h:65
virtual void unsubscribe()
Definition: imagesift.cpp:89
image_transport::Subscriber _subImage
Definition: imagesift.h:74
bool detect(posedetection_msgs::Feature0D &features, const sensor_msgs::Image &imagemsg, const sensor_msgs::Image::ConstPtr &mask_ptr)
Definition: imagesift.cpp:114
virtual void subscribe()
Definition: imagesift.cpp:74
boost::mutex _mutex
Definition: imagesift.h:71
ros::Subscriber _subInfo
Definition: imagesift.h:80
boost::shared_ptr< image_transport::ImageTransport > _it
Definition: imagesift.h:72
void imageCb(const sensor_msgs::ImageConstPtr &msg_ptr, const sensor_msgs::ImageConstPtr &mask_ptr)
Definition: imagesift.cpp:212


imagesift
Author(s): Rosen Diankov (rdiankov@cs.cmu.edu), Kei Okada
autogenerated on Mon May 3 2021 03:03:10