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/or 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 
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
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 {
60  // libsiftfast has so many static global variables. It causes segmentation fault when more than 2 imagesift nodelets are loaded into the same nodelet manager. This global variable enable more than 2 threads to use libsiftfast's variables. This means, libsiftfast becomes slow when you load 2 imagesift nodelets.
61  static boost::mutex _g_siftfast_mutex;
62 
63  class SiftNode: public jsk_topic_tools::DiagnosticNodelet
64  {
65  public:
67  sensor_msgs::Image,
68  sensor_msgs::Image > SyncPolicy;
70  SiftNode(): DiagnosticNodelet("SiftNode") {}
71  virtual ~SiftNode();
72  protected:
73  bool _bInfoInitialized;
74  bool _useMask;
75  boost::mutex _mutex;
79  // for useMask
87  posedetection_msgs::ImageFeature0D _sift_msg;
88 
89  virtual void onInit();
90  virtual void subscribe();
91  virtual void unsubscribe();
92  void infoCb(const sensor_msgs::CameraInfoConstPtr& msg_ptr);
93  bool detectCb(posedetection_msgs::Feature0DDetect::Request& req,
94  posedetection_msgs::Feature0DDetect::Response& res);
95  bool detect(posedetection_msgs::Feature0D& features,
96  const sensor_msgs::Image& imagemsg,
97  const sensor_msgs::Image::ConstPtr& mask_ptr);
98  void imageCb(const sensor_msgs::ImageConstPtr& msg_ptr,
99  const sensor_msgs::ImageConstPtr& mask_ptr);
100  void imageCb(const sensor_msgs::ImageConstPtr& msg_ptr);
101  private:
102  };
103 }
104 
105 #endif
imagesift::SiftNode::lasttime
ros::WallTime lasttime
Definition: imagesift.h:101
node_handle.h
imagesift
Definition: imagesift.h:58
ros::Publisher
imagesift::SiftNode::subscribe
virtual void subscribe()
Definition: imagesift.cpp:87
boost::shared_ptr< image_transport::ImageTransport >
imagesift::SiftNode::imageCb
void imageCb(const sensor_msgs::ImageConstPtr &msg_ptr, const sensor_msgs::ImageConstPtr &mask_ptr)
Definition: imagesift.cpp:226
imagesift::SiftNode::onInit
virtual void onInit()
Definition: imagesift.cpp:53
imagesift::SiftNode::infoCb
void infoCb(const sensor_msgs::CameraInfoConstPtr &msg_ptr)
Definition: imagesift.cpp:114
imagesift::SiftNode::_bInfoInitialized
bool _bInfoInitialized
Definition: imagesift.h:105
imagesift::SiftNode::_subInfo
ros::Subscriber _subInfo
Definition: imagesift.h:116
imagesift::SiftNode::~SiftNode
virtual ~SiftNode()
Definition: imagesift.cpp:74
message_filters::Subscriber< sensor_msgs::Image >
ros::ServiceServer
image_transport::Subscriber
subscriber_filter.h
imagesift::SiftNode::_subImageWithMask
message_filters::Subscriber< sensor_msgs::Image > _subImageWithMask
Definition: imagesift.h:112
subscriber.h
imagesift::SiftNode::_useMask
bool _useMask
Definition: imagesift.h:106
imagesift::SiftNode
Definition: imagesift.h:95
imagesift::SiftNode::_sync
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > _sync
Definition: imagesift.h:114
ros::WallTime
imagesift::SiftNode::_it
boost::shared_ptr< image_transport::ImageTransport > _it
Definition: imagesift.h:108
image_transport.h
exact_time.h
imagesift::SiftNode::SiftNode
SiftNode()
Definition: imagesift.h:102
imagesift::_g_siftfast_mutex
static boost::mutex _g_siftfast_mutex
Definition: imagesift.h:93
imagesift::SiftNode::_subMask
message_filters::Subscriber< sensor_msgs::Image > _subMask
Definition: imagesift.h:113
cv_bridge.h
imagesift::SiftNode::_hints
image_transport::TransportHints _hints
Definition: imagesift.h:109
imagesift::SiftNode::_sift_msg
posedetection_msgs::ImageFeature0D _sift_msg
Definition: imagesift.h:119
synchronizer.h
imagesift::SiftNode::_pubSift
ros::Publisher _pubSift
Definition: imagesift.h:118
imagesift::SiftNode::_pubFeatures
ros::Publisher _pubFeatures
Definition: imagesift.h:117
imagesift::SiftNode::detect
bool detect(posedetection_msgs::Feature0D &features, const sensor_msgs::Image &imagemsg, const sensor_msgs::Image::ConstPtr &mask_ptr)
Definition: imagesift.cpp:127
image_transport::TransportHints
message_filters::sync_policies::ExactTime
imagesift::SiftNode::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicy
Definition: imagesift.h:100
imagesift::SiftNode::unsubscribe
virtual void unsubscribe()
Definition: imagesift.cpp:102
imagesift::SiftNode::_subImage
image_transport::Subscriber _subImage
Definition: imagesift.h:110
imagesift::SiftNode::_mutex
boost::mutex _mutex
Definition: imagesift.h:107
ros::Subscriber
imagesift::SiftNode::_srvDetect
ros::ServiceServer _srvDetect
Definition: imagesift.h:115
imagesift::SiftNode::detectCb
bool detectCb(posedetection_msgs::Feature0DDetect::Request &req, posedetection_msgs::Feature0DDetect::Response &res)
Definition: imagesift.cpp:121


imagesift
Author(s): Rosen Diankov (rdiankov@cs.cmu.edu), Kei Okada
autogenerated on Fri May 16 2025 03:11:08