00001 #ifndef VISP_TRACKER_TRACKER_CLIENT_HH 00002 # define VISP_TRACKER_TRACKER_CLIENT_HH 00003 # include <boost/filesystem/fstream.hpp> 00004 # include <boost/filesystem/path.hpp> 00005 # include <boost/thread/recursive_mutex.hpp> 00006 00007 # include <dynamic_reconfigure/server.h> 00008 00009 # include <image_proc/advertisement_checker.h> 00010 00011 # include <image_transport/image_transport.h> 00012 # include <image_transport/subscriber_filter.h> 00013 00014 # include <message_filters/subscriber.h> 00015 # include <message_filters/sync_policies/approximate_time.h> 00016 # include <message_filters/synchronizer.h> 00017 00018 # include <sensor_msgs/Image.h> 00019 # include <sensor_msgs/CameraInfo.h> 00020 00021 # include <resource_retriever/retriever.h> 00022 00023 # include <visp_tracker/ModelBasedSettingsConfig.h> 00024 # include <visp_tracker/MovingEdgeSites.h> 00025 00026 # include <visp/vpCameraParameters.h> 00027 # include <visp/vpHomogeneousMatrix.h> 00028 # include <visp/vpImage.h> 00029 # include <visp/vpMbTracker.h> 00030 # include <visp/vpMe.h> 00031 # include <visp/vpKltOpencv.h> 00032 # include <visp/vpPose.h> 00033 00034 00035 namespace visp_tracker 00036 { 00037 class TrackerClient 00038 { 00039 public: 00040 typedef vpImage<unsigned char> image_t; 00041 typedef std::vector<vpPoint> points_t; 00042 typedef std::vector<vpImagePoint> imagePoints_t; 00043 00044 typedef dynamic_reconfigure::Server<visp_tracker::ModelBasedSettingsConfig> 00045 reconfigureSrv_t; 00046 00047 typedef dynamic_reconfigure::Server 00048 <visp_tracker::ModelBasedSettingsConfig>::CallbackType 00049 reconfigureCallback_t; 00050 00051 00052 TrackerClient(ros::NodeHandle& nh, 00053 ros::NodeHandle& privateNh, 00054 volatile bool& exiting, 00055 unsigned queueSize = 5u); 00056 00057 ~TrackerClient(); 00058 00059 void spin(); 00060 protected: 00062 void checkInputs(); 00063 00064 void loadModel(); 00065 00066 bool validatePose(const vpHomogeneousMatrix& cMo); 00067 vpHomogeneousMatrix loadInitialPose(); 00068 void saveInitialPose(const vpHomogeneousMatrix& cMo); 00069 points_t loadInitializationPoints(); 00070 00071 void init(); 00072 void initPoint(unsigned& i, 00073 points_t& points, 00074 imagePoints_t& imagePoints, 00075 ros::Rate& rate, 00076 vpPose& pose); 00077 00078 00079 void waitForImage(); 00080 00081 void sendcMo(const vpHomogeneousMatrix& cMo); 00082 00083 std::string fetchResource(const std::string&); 00084 bool makeModelFile(boost::filesystem::ofstream& modelStream, 00085 const std::string& resourcePath, 00086 std::string& fullModelPath); 00087 00088 private: 00089 bool exiting () 00090 { 00091 return exiting_ || !ros::ok(); 00092 } 00093 00094 volatile bool& exiting_; 00095 00096 unsigned queueSize_; 00097 00098 ros::NodeHandle& nodeHandle_; 00099 ros::NodeHandle& nodeHandlePrivate_; 00100 00101 image_transport::ImageTransport imageTransport_; 00102 00103 image_t image_; 00104 00105 std::string modelPath_; 00106 std::string modelName_; 00107 00108 std::string cameraPrefix_; 00109 std::string rectifiedImageTopic_; 00110 std::string cameraInfoTopic_; 00111 std::string trackerType_; 00112 00113 boost::filesystem::path vrmlPath_; 00114 boost::filesystem::path initPath_; 00115 00116 image_transport::CameraSubscriber cameraSubscriber_; 00117 00118 boost::recursive_mutex mutex_; 00119 reconfigureSrv_t reconfigureSrv_; 00120 00121 std_msgs::Header header_; 00122 sensor_msgs::CameraInfoConstPtr info_; 00123 00124 vpMe movingEdge_; 00125 vpKltOpencv kltTracker_; 00126 vpCameraParameters cameraParameters_; 00127 vpMbTracker *tracker_; 00128 00129 bool startFromSavedPose_; 00130 bool confirmInit_; 00131 00133 image_proc::AdvertisementChecker checkInputs_; 00134 00135 resource_retriever::Retriever resourceRetriever_; 00136 }; 00137 } // end of namespace visp_tracker. 00138 00139 #endif //! VISP_TRACKER_TRACKER_CLIENT_HH