tracker.hh
Go to the documentation of this file.
00001 #ifndef VISP_TRACKER_TRACKER_HH
00002 # define VISP_TRACKER_TRACKER_HH
00003 # include <boost/filesystem/path.hpp>
00004 # include <boost/thread/recursive_mutex.hpp>
00005 
00006 # include <dynamic_reconfigure/server.h>
00007 
00008 # include <image_proc/advertisement_checker.h>
00009 
00010 # include <image_transport/image_transport.h>
00011 
00012 # include <geometry_msgs/TwistStamped.h>
00013 
00014 # include <sensor_msgs/Image.h>
00015 # include <sensor_msgs/CameraInfo.h>
00016 
00017 # include <tf/transform_broadcaster.h>
00018 # include <tf/transform_listener.h>
00019 
00020 # include <visp_tracker/Init.h>
00021 # include <visp_tracker/ModelBasedSettingsConfig.h>
00022 # include <visp_tracker/MovingEdgeSites.h>
00023 # include <visp_tracker/KltPoints.h>
00024 
00025 # include <visp/vpCameraParameters.h>
00026 # include <visp/vpHomogeneousMatrix.h>
00027 # include <visp/vpImage.h>
00028 # include <visp/vpMbTracker.h>
00029 #include <visp/vpMbEdgeKltTracker.h>
00030 # include <visp/vpMe.h>
00031 # include <string>
00032 
00033 namespace visp_tracker
00034 {
00035   class Tracker
00036   {
00037   public:
00038     typedef vpImage<unsigned char> image_t;
00039 
00040     typedef dynamic_reconfigure::Server<visp_tracker::ModelBasedSettingsConfig>
00041     reconfigureSrv_t;
00042 
00043     typedef boost::function<bool (visp_tracker::Init::Request&,
00044                                   visp_tracker::Init::Response& res)>
00045     initCallback_t;
00046 
00047     enum State
00048       {
00049         WAITING_FOR_INITIALIZATION,
00050         TRACKING,
00051         LOST
00052       };
00053 
00054 
00055     Tracker (ros::NodeHandle& nh,
00056              ros::NodeHandle& privateNh,
00057              volatile bool& exiting,
00058              unsigned queueSize = 5u);
00059     
00060     ~Tracker();
00061     
00062     void spin();
00063   protected:
00064     bool initCallback(visp_tracker::Init::Request& req,
00065                       visp_tracker::Init::Response& res);
00066 
00067     void updateMovingEdgeSites(visp_tracker::MovingEdgeSitesPtr sites);
00068     void updateKltPoints(visp_tracker::KltPointsPtr klt);
00069 
00070     void checkInputs();
00071     void waitForImage();
00072 
00073     void objectPositionHintCallback
00074     (const geometry_msgs::TransformStampedConstPtr&);
00075   private:
00076     bool exiting ()
00077     {
00078       return exiting_ || !ros::ok();
00079     }
00080 
00081     void spinOnce ()
00082     {
00083       //callbackQueue_.callAvailable(ros::WallDuration(0));
00084       ros::spinOnce ();
00085     }
00086 
00087     volatile bool& exiting_;
00088 
00089     unsigned queueSize_;
00090 
00091     ros::NodeHandle& nodeHandle_;
00092     ros::NodeHandle& nodeHandlePrivate_;
00093     image_transport::ImageTransport imageTransport_;
00094 
00095     State state_;
00096     std::string trackerType_;
00097 
00098     image_t image_;
00099 
00100     std::string cameraPrefix_;
00101     std::string rectifiedImageTopic_;
00102     std::string cameraInfoTopic_;
00103 
00104     boost::filesystem::path vrmlPath_;
00105 
00106     image_transport::CameraSubscriber cameraSubscriber_;
00107 
00108     boost::recursive_mutex mutex_;
00109     reconfigureSrv_t reconfigureSrv_;
00110 
00111     ros::Publisher resultPublisher_;
00112     ros::Publisher transformationPublisher_;
00113     tf::TransformBroadcaster tfBroadcaster_;
00114     ros::Publisher movingEdgeSitesPublisher_;
00115     ros::Publisher kltPointsPublisher_;
00116 
00117     ros::ServiceServer initService_;
00118 
00119     std_msgs::Header header_;
00120     sensor_msgs::CameraInfoConstPtr info_;
00121 
00122     vpKltOpencv kltTracker_;
00123     vpMe movingEdge_;
00124     vpCameraParameters cameraParameters_;
00125     vpMbTracker* tracker_;
00126 
00127     unsigned lastTrackedImage_;
00128 
00130     image_proc::AdvertisementChecker checkInputs_;
00131 
00132     vpHomogeneousMatrix cMo_;
00133 
00134     tf::TransformListener listener_;
00135     std::string worldFrameId_;
00136     bool compensateRobotMotion_;
00137 
00138     tf::TransformBroadcaster transformBroadcaster_;
00139     std::string childFrameId_;
00140 
00141     ros::Subscriber objectPositionHintSubscriber_;
00142     geometry_msgs::TransformStamped objectPositionHint_;
00143   };
00144 } // end of namespace visp_tracker.
00145 
00146 #endif //! VISP_TRACKER_TRACKER_HH


visp_tracker
Author(s): Thomas Moulard
autogenerated on Mon Oct 6 2014 08:40:35