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 <image_proc/advertisement_checker.h> 00007 00008 # include <image_transport/image_transport.h> 00009 # include <image_transport/subscriber_filter.h> 00010 00011 # include <message_filters/subscriber.h> 00012 # include <message_filters/sync_policies/approximate_time.h> 00013 # include <message_filters/synchronizer.h> 00014 00015 # include <sensor_msgs/Image.h> 00016 # include <sensor_msgs/CameraInfo.h> 00017 00018 # include <visp_tracker/MovingEdgeSites.h> 00019 # include <visp_tracker/TrackingResult.h> 00020 00021 # include <visp/vpCameraParameters.h> 00022 # include <visp/vpImage.h> 00023 # include <visp/vpMbEdgeTracker.h> 00024 00025 namespace visp_tracker 00026 { 00028 class TrackerViewer 00029 { 00030 public: 00032 typedef vpImage<unsigned char> image_t; 00033 00041 typedef message_filters::sync_policies::ApproximateTime< 00042 sensor_msgs::Image, sensor_msgs::CameraInfo, 00043 visp_tracker::TrackingResult, visp_tracker::MovingEdgeSites 00044 > syncPolicy_t; 00045 00047 TrackerViewer(unsigned queueSize = 5u); 00048 00051 void spin(); 00052 protected: 00054 void initializeTracker(); 00055 00057 void checkInputs(); 00058 00060 void waitForImage(); 00061 00063 void callback(const sensor_msgs::ImageConstPtr& imageConst, 00064 const sensor_msgs::CameraInfoConstPtr& infoConst, 00065 const visp_tracker::TrackingResult::ConstPtr& trackingResult, 00066 const visp_tracker::MovingEdgeSites::ConstPtr& sitesConst); 00067 00068 void timerCallback(); 00069 00071 void displayMovingEdgeSites(); 00072 00073 private: 00075 unsigned queueSize_; 00076 00078 ros::NodeHandle nodeHandle_; 00080 image_transport::ImageTransport imageTransport_; 00081 00082 00085 00087 std::string rectifiedImageTopic_; 00089 std::string cameraInfoTopic_; 00090 00092 00093 00095 boost::filesystem::path vrmlPath_; 00096 00098 image_proc::AdvertisementChecker checkInputs_; 00099 00101 vpMbEdgeTracker tracker_; 00103 vpCameraParameters cameraParameters_; 00105 image_t image_; 00106 00108 sensor_msgs::CameraInfoConstPtr info_; 00110 boost::optional<vpHomogeneousMatrix> cMo_; 00112 visp_tracker::MovingEdgeSites::ConstPtr sites_; 00113 00117 image_transport::SubscriberFilter imageSubscriber_; 00119 message_filters::Subscriber<sensor_msgs::CameraInfo> cameraInfoSubscriber_; 00121 message_filters::Subscriber<visp_tracker::TrackingResult> 00122 trackingResultSubscriber_; 00124 message_filters::Subscriber<visp_tracker::MovingEdgeSites> 00125 movingEdgeSitesSubscriber_; 00126 00128 message_filters::Synchronizer<syncPolicy_t> synchronizer_; 00130 00133 ros::WallTimer timer_; 00134 unsigned countAll_; 00135 unsigned countImages_; 00136 unsigned countCameraInfo_; 00137 unsigned countTrackingResult_; 00138 unsigned countMovingEdgeSites_; 00140 }; 00141 } // end of namespace visp_tracker 00142 00143 #endif //! VISP_TRACKER_TRACKER_VIEWER_HH