tracker-viewer.hh
Go to the documentation of this file.
1 #ifndef VISP_TRACKER_TRACKER_VIEWER_HH
2 # define VISP_TRACKER_TRACKER_VIEWER_HH
3 # include <boost/filesystem/path.hpp>
4 # include <boost/optional.hpp>
5 
6 # include <geometry_msgs/PoseWithCovarianceStamped.h>
7 
9 
12 
16 
17 # include <sensor_msgs/Image.h>
18 # include <sensor_msgs/CameraInfo.h>
19 
20 # include <visp_tracker/Init.h>
21 # include <visp_tracker/MovingEdgeSites.h>
22 # include <visp_tracker/KltPoints.h>
23 
24 # include <visp/vpCameraParameters.h>
25 # include <visp/vpImage.h>
26 # include <visp/vpMbEdgeTracker.h>
27 
28 namespace visp_tracker
29 {
32  {
33  public:
35  typedef vpImage<unsigned char> image_t;
36 
37 
38  typedef boost::function<bool (visp_tracker::Init::Request&,
39  visp_tracker::Init::Response& res)>
41 
42  typedef boost::function<bool (visp_tracker::Init::Request&,
43  visp_tracker::Init::Response& res)>
45 
54  sensor_msgs::Image, sensor_msgs::CameraInfo,
55  geometry_msgs::PoseWithCovarianceStamped,
56  visp_tracker::MovingEdgeSites,
57  visp_tracker::KltPoints
59 
62  ros::NodeHandle& privateNh,
63  volatile bool& exiting,
64  unsigned queueSize = 5u);
65 
68  void spin();
69  protected:
71  void initializeTracker();
72 
74  void loadCommonParameters();
75 
77  void checkInputs();
78 
80  void waitForImage();
81 
82  bool initCallback(visp_tracker::Init::Request& req,
83  visp_tracker::Init::Response& res);
84 
85  bool reconfigureCallback(visp_tracker::Init::Request& req,
86  visp_tracker::Init::Response& res);
87 
89  void
90  callback
91  (const sensor_msgs::ImageConstPtr& imageConst,
92  const sensor_msgs::CameraInfoConstPtr& infoConst,
93  const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& trackingResult,
94  const visp_tracker::MovingEdgeSites::ConstPtr& sitesConst,
95  const visp_tracker::KltPoints::ConstPtr& kltConst);
96 
97  void timerCallback();
98 
100  void displayMovingEdgeSites();
102  void displayKltPoints();
103 
104  private:
105  bool exiting ()
106  {
107  return exiting_ || !ros::ok();
108  }
109 
110  volatile bool& exiting_;
111 
113  unsigned queueSize_;
114 
117 
120 
121  double frameSize_;
122 
125 
127  std::string rectifiedImageTopic_;
129  std::string cameraInfoTopic_;
130 
132 
135 
138 
140  std::string trackerName_;
141 
143  boost::filesystem::path modelPath_;
144 
147 
149  vpMbEdgeTracker tracker_;
151  vpCameraParameters cameraParameters_;
153  image_t image_;
154 
156  sensor_msgs::CameraInfoConstPtr info_;
158  boost::optional<vpHomogeneousMatrix> cMo_;
160  visp_tracker::MovingEdgeSites::ConstPtr sites_;
162  visp_tracker::KltPoints::ConstPtr klt_;
163 
179 
183 
187  unsigned countAll_;
188  unsigned countImages_;
192  unsigned countKltPoints_;
194  };
195 } // end of namespace visp_tracker
196 
197 #endif
image_transport::ImageTransport imageTransport_
Image transport used to receive images.
vpImage< unsigned char > image_t
ViSP image type.
ros::NodeHandle & nodeHandle_
void displayMovingEdgeSites()
Display moving edge sites.
void waitForImage()
Hang until the first image is received.
message_filters::Subscriber< geometry_msgs::PoseWithCovarianceStamped > trackingResultSubscriber_
Subscriber to tracking result topic.
std::string rectifiedImageTopic_
Full topic name for rectified image.
boost::function< bool(visp_tracker::Init::Request &, visp_tracker::Init::Response &res)> initCallback_t
boost::function< bool(visp_tracker::Init::Request &, visp_tracker::Init::Response &res)> reconfigureCallback_t
ros::ServiceServer reconfigureService_
Service called when user is reconfiguring tracker node.
message_filters::Subscriber< visp_tracker::KltPoints > kltPointsSubscriber_
Subscriber to KLT point topics.
visp_tracker::KltPoints::ConstPtr klt_
Shared pointer to latest received KLT point positions.
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
std::string trackerName_
Name of the tracker used in this viewer node.
TrackerViewer(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
Constructor.
ros::NodeHandle & nodeHandlePrivate_
vpMbEdgeTracker tracker_
ViSP edge tracker.
void displayKltPoints()
Display KLT points that are tracked.
boost::filesystem::path modelPath_
Model path.
image_t image_
ViSP image.
bool initCallback(visp_tracker::Init::Request &req, visp_tracker::Init::Response &res)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::CameraInfo, geometry_msgs::PoseWithCovarianceStamped, visp_tracker::MovingEdgeSites, visp_tracker::KltPoints > syncPolicy_t
Synchronization policy.
bool reconfigureCallback(visp_tracker::Init::Request &req, visp_tracker::Init::Response &res)
void callback(const sensor_msgs::ImageConstPtr &imageConst, const sensor_msgs::CameraInfoConstPtr &infoConst, const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &trackingResult, const visp_tracker::MovingEdgeSites::ConstPtr &sitesConst, const visp_tracker::KltPoints::ConstPtr &kltConst)
Callback used to received synchronized data.
ROSCPP_DECL bool ok()
sensor_msgs::CameraInfoConstPtr info_
Shared pointer to latest received camera information.
image_transport::SubscriberFilter imageSubscriber_
ros::ServiceServer initService_
Service called when user ends tracker_client node.
void checkInputs()
Make sure the topics we subscribe already exist.
message_filters::Synchronizer< syncPolicy_t > synchronizer_
Synchronizer with approximate time policy.
vpCameraParameters cameraParameters_
ViSP camera parameters.
Monitors the tracking result provided by the tracking node.
message_filters::Subscriber< visp_tracker::MovingEdgeSites > movingEdgeSitesSubscriber_
Subscriber to moving edge sites topics.
void initializeTracker()
Initialize the tracker.
unsigned queueSize_
Queue size for all subscribers.
std::string cameraInfoTopic_
Full topic name for camera information.
boost::optional< vpHomogeneousMatrix > cMo_
Last tracked object position, set to none if tracking failed.
void spin()
Display camera image, tracked object position and moving edge sites.
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSubscriber_
Subscriber to camera information topic.
visp_tracker::MovingEdgeSites::ConstPtr sites_
Shared pointer to latest received moving edge sites.
void loadCommonParameters()
Initialize the common parameters (visibility angles, etc)


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