00001 #ifndef VISP_TRACKER_TRACKER_CLIENT_HH 00002 # define VISP_TRACKER_TRACKER_CLIENT_HH 00003 # include <boost/filesystem/path.hpp> 00004 00005 # include <dynamic_reconfigure/server.h> 00006 00007 # include <image_proc/advertisement_checker.h> 00008 00009 # include <image_transport/image_transport.h> 00010 # include <image_transport/subscriber_filter.h> 00011 00012 # include <message_filters/subscriber.h> 00013 # include <message_filters/sync_policies/approximate_time.h> 00014 # include <message_filters/synchronizer.h> 00015 00016 # include <sensor_msgs/Image.h> 00017 # include <sensor_msgs/CameraInfo.h> 00018 00019 # include <visp_tracker/MovingEdgeConfig.h> 00020 # include <visp_tracker/MovingEdgeSites.h> 00021 # include <visp_tracker/TrackingResult.h> 00022 00023 # include <visp/vpCameraParameters.h> 00024 # include <visp/vpHomogeneousMatrix.h> 00025 # include <visp/vpImage.h> 00026 # include <visp/vpMbEdgeTracker.h> 00027 # include <visp/vpPose.h> 00028 00029 00030 namespace visp_tracker 00031 { 00032 class TrackerClient 00033 { 00034 public: 00035 typedef vpImage<unsigned char> image_t; 00036 typedef std::vector<vpPoint> points_t; 00037 typedef std::vector<vpImagePoint> imagePoints_t; 00038 00039 typedef dynamic_reconfigure::Server<visp_tracker::MovingEdgeConfig> 00040 reconfigureSrv_t; 00041 00042 typedef dynamic_reconfigure::Server 00043 <visp_tracker::MovingEdgeConfig>::CallbackType 00044 reconfigureCallback_t; 00045 00046 00047 TrackerClient(unsigned queueSize = 5u); 00048 00049 void spin(); 00050 protected: 00052 void checkInputs(); 00053 00054 void loadModel(); 00055 00056 vpHomogeneousMatrix loadInitialPose(); 00057 void saveInitialPose(const vpHomogeneousMatrix& cMo); 00058 points_t loadInitializationPoints(); 00059 00060 void initClick(); 00061 void initPoint(unsigned& i, 00062 points_t& points, 00063 imagePoints_t& imagePoints, 00064 ros::Rate& rate, 00065 vpPose& pose); 00066 00067 00068 void waitForImage(); 00069 00070 void sendcMo(const vpHomogeneousMatrix& cMo); 00071 private: 00072 unsigned queueSize_; 00073 00074 ros::NodeHandle nodeHandle_; 00075 image_transport::ImageTransport imageTransport_; 00076 00077 image_t image_; 00078 00079 std::string modelPath_; 00080 std::string modelName_; 00081 00082 std::string cameraPrefix_; 00083 std::string rectifiedImageTopic_; 00084 std::string cameraInfoTopic_; 00085 00086 boost::filesystem::path vrmlPath_; 00087 boost::filesystem::path initPath_; 00088 00089 image_transport::CameraSubscriber cameraSubscriber_; 00090 00091 reconfigureSrv_t reconfigureSrv_; 00092 00093 std_msgs::Header header_; 00094 sensor_msgs::CameraInfoConstPtr info_; 00095 00096 vpMe movingEdge_; 00097 vpCameraParameters cameraParameters_; 00098 vpMbEdgeTracker tracker_; 00099 00100 bool startFromSavedPose_; 00101 bool confirmInit_; 00102 00104 image_proc::AdvertisementChecker checkInputs_; 00105 }; 00106 } // end of namespace visp_tracker. 00107 00108 #endif //! VISP_TRACKER_TRACKER_CLIENT_HH