Go to the documentation of this file.00001 #ifndef VISP_TRACKER_TRACKER_VIEWER_HH
00002 # define VISP_TRACKER_TRACKER_VIEWER_HH
00003 # include <boost/filesystem/path.hpp>
00004 # include <boost/optional.hpp>
00005
00006 # include <geometry_msgs/PoseWithCovarianceStamped.h>
00007
00008 # include <image_proc/advertisement_checker.h>
00009
00010 # include <image_transport/image_transport.h>
00011 # include <image_transport/subscriber_filter.h>
00012
00013 # include <message_filters/subscriber.h>
00014 # include <message_filters/sync_policies/approximate_time.h>
00015 # include <message_filters/synchronizer.h>
00016
00017 # include <sensor_msgs/Image.h>
00018 # include <sensor_msgs/CameraInfo.h>
00019
00020 # include <visp_tracker/MovingEdgeSites.h>
00021 # include <visp_tracker/KltPoints.h>
00022
00023 # include <visp/vpCameraParameters.h>
00024 # include <visp/vpImage.h>
00025 # include <visp/vpMbEdgeTracker.h>
00026
00027 namespace visp_tracker
00028 {
00030 class TrackerViewer
00031 {
00032 public:
00034 typedef vpImage<unsigned char> image_t;
00035
00043 typedef message_filters::sync_policies::ApproximateTime<
00044 sensor_msgs::Image, sensor_msgs::CameraInfo,
00045 geometry_msgs::PoseWithCovarianceStamped,
00046 visp_tracker::MovingEdgeSites,
00047 visp_tracker::KltPoints
00048 > syncPolicy_t;
00049
00051 TrackerViewer(ros::NodeHandle& nh,
00052 ros::NodeHandle& privateNh,
00053 volatile bool& exiting,
00054 unsigned queueSize = 5u);
00055
00058 void spin();
00059 protected:
00061 void initializeTracker();
00062
00064 void checkInputs();
00065
00067 void waitForImage();
00068
00070 void
00071 callback
00072 (const sensor_msgs::ImageConstPtr& imageConst,
00073 const sensor_msgs::CameraInfoConstPtr& infoConst,
00074 const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& trackingResult,
00075 const visp_tracker::MovingEdgeSites::ConstPtr& sitesConst,
00076 const visp_tracker::KltPoints::ConstPtr& kltConst);
00077
00078 void timerCallback();
00079
00081 void displayMovingEdgeSites();
00083 void displayKltPoints();
00084
00085 private:
00086 bool exiting ()
00087 {
00088 return exiting_ || !ros::ok();
00089 }
00090
00091 volatile bool& exiting_;
00092
00094 unsigned queueSize_;
00095
00096 ros::NodeHandle& nodeHandle_;
00097 ros::NodeHandle& nodeHandlePrivate_;
00098
00100 image_transport::ImageTransport imageTransport_;
00101
00102
00105
00107 std::string rectifiedImageTopic_;
00109 std::string cameraInfoTopic_;
00110
00112
00113
00115 boost::filesystem::path vrmlPath_;
00116
00118 image_proc::AdvertisementChecker checkInputs_;
00119
00121 vpMbEdgeTracker tracker_;
00123 vpCameraParameters cameraParameters_;
00125 image_t image_;
00126
00128 sensor_msgs::CameraInfoConstPtr info_;
00130 boost::optional<vpHomogeneousMatrix> cMo_;
00132 visp_tracker::MovingEdgeSites::ConstPtr sites_;
00134 visp_tracker::KltPoints::ConstPtr klt_;
00135
00139 image_transport::SubscriberFilter imageSubscriber_;
00141 message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoSubscriber_;
00143 message_filters::Subscriber<geometry_msgs::PoseWithCovarianceStamped>
00144 trackingResultSubscriber_;
00146 message_filters::Subscriber<visp_tracker::MovingEdgeSites>
00147 movingEdgeSitesSubscriber_;
00149 message_filters::Subscriber<visp_tracker::KltPoints>
00150 kltPointsSubscriber_;
00151
00153 message_filters::Synchronizer<syncPolicy_t> synchronizer_;
00155
00158 ros::WallTimer timer_;
00159 unsigned countAll_;
00160 unsigned countImages_;
00161 unsigned countCameraInfo_;
00162 unsigned countTrackingResult_;
00163 unsigned countMovingEdgeSites_;
00164 unsigned countKltPoints_;
00166 };
00167 }
00168
00169 #endif //! VISP_TRACKER_TRACKER_VIEWER_HH