tracker.hh
Go to the documentation of this file.
1 #ifndef VISP_TRACKER_TRACKER_HH
2 # define VISP_TRACKER_TRACKER_HH
3 # include <boost/filesystem/path.hpp>
4 # include <boost/thread/recursive_mutex.hpp>
5 
6 # include <dynamic_reconfigure/server.h>
7 
9 
11 
12 # include <geometry_msgs/TwistStamped.h>
13 
14 # include <sensor_msgs/Image.h>
15 # include <sensor_msgs/CameraInfo.h>
16 
18 # include <tf/transform_listener.h>
19 
20 # include <visp_tracker/Init.h>
21 # include <visp_tracker/ModelBasedSettingsConfig.h>
22 # include <visp_tracker/ModelBasedSettingsKltConfig.h>
23 # include <visp_tracker/ModelBasedSettingsEdgeConfig.h>
24 # include <visp_tracker/MovingEdgeSites.h>
25 # include <visp_tracker/KltPoints.h>
26 
27 # include <visp/vpCameraParameters.h>
28 # include <visp/vpHomogeneousMatrix.h>
29 # include <visp/vpImage.h>
30 
31 # include <visp/vpMbTracker.h>
32 # include <visp/vpMbEdgeKltTracker.h>
33 
34 # include <visp/vpMe.h>
35 # include <string>
36 
37 namespace visp_tracker
38 {
39  class Tracker
40  {
41  public:
42  typedef vpImage<unsigned char> image_t;
43 
44  typedef boost::function<bool (visp_tracker::Init::Request&,
45  visp_tracker::Init::Response& res)>
47 
48  template<class ConfigType>
50  typedef dynamic_reconfigure::Server<ConfigType> reconfigureSrv_t;
51  };
52 
53  enum State
54  {
58  };
59 
60 
62  ros::NodeHandle& privateNh,
63  volatile bool& exiting,
64  unsigned queueSize = 5u);
65 
66  ~Tracker();
67 
68  void spin();
69  protected:
70  bool initCallback(visp_tracker::Init::Request& req,
71  visp_tracker::Init::Response& res);
72 
73  void updateMovingEdgeSites(visp_tracker::MovingEdgeSitesPtr sites);
74  void updateKltPoints(visp_tracker::KltPointsPtr klt);
75 
76  void checkInputs();
77  void waitForImage();
78 
80  (const geometry_msgs::TransformStampedConstPtr&);
81  private:
82  bool exiting ()
83  {
84  return exiting_ || !ros::ok();
85  }
86 
87  void spinOnce ()
88  {
89  //callbackQueue_.callAvailable(ros::WallDuration(0));
90  ros::spinOnce ();
91  }
92 
93  volatile bool& exiting_;
94 
95  unsigned queueSize_;
96 
100 
102  std::string trackerType_;
103 
104  image_t image_;
105 
106  std::string cameraPrefix_;
107  std::string rectifiedImageTopic_;
108  std::string cameraInfoTopic_;
109 
110  boost::filesystem::path modelPath_;
111 
113 
114  boost::recursive_mutex mutex_;
115 
119 
125 
127 
128  std_msgs::Header header_;
129  sensor_msgs::CameraInfoConstPtr info_;
130 
131  vpKltOpencv kltTracker_;
133  vpCameraParameters cameraParameters_;
134  vpMbTracker* tracker_;
135 
137 
140 
141  vpHomogeneousMatrix cMo_;
142 
144  std::string worldFrameId_;
146 
148  std::string childFrameId_;
149 
151  geometry_msgs::TransformStamped objectPositionHint_;
152  };
153 } // end of namespace visp_tracker.
154 
155 #endif
std::string rectifiedImageTopic_
Definition: tracker.hh:107
tf::TransformBroadcaster tfBroadcaster_
Definition: tracker.hh:122
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsEdgeConfig >::reconfigureSrv_t * reconfigureEdgeSrv_
Definition: tracker.hh:118
void updateKltPoints(visp_tracker::KltPointsPtr klt)
void objectPositionHintCallback(const geometry_msgs::TransformStampedConstPtr &)
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
Definition: tracker.hh:139
std_msgs::Header header_
Definition: tracker.hh:128
std::string cameraInfoTopic_
Definition: tracker.hh:108
std::string worldFrameId_
Definition: tracker.hh:144
ros::Publisher resultPublisher_
Definition: tracker.hh:120
ros::Publisher movingEdgeSitesPublisher_
Definition: tracker.hh:123
std::string childFrameId_
Definition: tracker.hh:148
vpKltOpencv kltTracker_
Definition: tracker.hh:131
Tracker(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
boost::recursive_mutex mutex_
Definition: tracker.hh:114
image_transport::ImageTransport imageTransport_
Definition: tracker.hh:99
ros::Subscriber objectPositionHintSubscriber_
Definition: tracker.hh:150
boost::filesystem::path modelPath_
Definition: tracker.hh:110
ros::NodeHandle & nodeHandle_
Definition: tracker.hh:97
bool initCallback(visp_tracker::Init::Request &req, visp_tracker::Init::Response &res)
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsKltConfig >::reconfigureSrv_t * reconfigureKltSrv_
Definition: tracker.hh:117
unsigned queueSize_
Definition: tracker.hh:95
geometry_msgs::TransformStamped objectPositionHint_
Definition: tracker.hh:151
std::string cameraPrefix_
Definition: tracker.hh:106
ROSCPP_DECL bool ok()
image_transport::CameraSubscriber cameraSubscriber_
Definition: tracker.hh:112
vpMbTracker * tracker_
Definition: tracker.hh:134
tf::TransformListener listener_
Definition: tracker.hh:143
sensor_msgs::CameraInfoConstPtr info_
Definition: tracker.hh:129
unsigned lastTrackedImage_
Definition: tracker.hh:136
void updateMovingEdgeSites(visp_tracker::MovingEdgeSitesPtr sites)
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsConfig >::reconfigureSrv_t * reconfigureSrv_
Definition: tracker.hh:116
tf::TransformBroadcaster transformBroadcaster_
Definition: tracker.hh:147
boost::function< bool(visp_tracker::Init::Request &, visp_tracker::Init::Response &res)> initCallback_t
Definition: tracker.hh:46
ros::ServiceServer initService_
Definition: tracker.hh:126
dynamic_reconfigure::Server< ConfigType > reconfigureSrv_t
Definition: tracker.hh:50
vpCameraParameters cameraParameters_
Definition: tracker.hh:133
volatile bool & exiting_
Definition: tracker.hh:93
ROSCPP_DECL void spinOnce()
ros::NodeHandle & nodeHandlePrivate_
Definition: tracker.hh:98
vpImage< unsigned char > image_t
Definition: tracker.hh:42
std::string trackerType_
Definition: tracker.hh:102
ros::Publisher kltPointsPublisher_
Definition: tracker.hh:124
vpHomogeneousMatrix cMo_
Definition: tracker.hh:141
ros::Publisher transformationPublisher_
Definition: tracker.hh:121


visp_tracker
Author(s): Thomas Moulard
autogenerated on Wed Jul 3 2019 19:48:07