tracker-client.hh
Go to the documentation of this file.
1 #ifndef VISP_TRACKER_TRACKER_CLIENT_HH
2 # define VISP_TRACKER_TRACKER_CLIENT_HH
3 # include <boost/filesystem/fstream.hpp>
4 # include <boost/filesystem/path.hpp>
5 # include <boost/thread/recursive_mutex.hpp>
6 
7 # include <dynamic_reconfigure/server.h>
8 
10 
13 
17 
18 # include <sensor_msgs/Image.h>
19 # include <sensor_msgs/CameraInfo.h>
20 
22 
23 # include <visp_tracker/ModelBasedSettingsConfig.h>
24 # include <visp_tracker/ModelBasedSettingsKltConfig.h>
25 # include <visp_tracker/ModelBasedSettingsEdgeConfig.h>
26 # include <visp_tracker/MovingEdgeSites.h>
27 
28 # include <visp/vpCameraParameters.h>
29 # include <visp/vpHomogeneousMatrix.h>
30 # include <visp/vpImage.h>
31 # include <visp/vpMbTracker.h>
32 # include <visp/vpMe.h>
33 # include <visp/vpKltOpencv.h>
34 # include <visp/vpPose.h>
35 
36 
37 namespace visp_tracker
38 {
40  {
41  public:
42  typedef vpImage<unsigned char> image_t;
43  typedef std::vector<vpPoint> points_t;
44  typedef std::vector<vpImagePoint> imagePoints_t;
45 
46  template<class ConfigType>
48  typedef dynamic_reconfigure::Server<ConfigType> reconfigureSrv_t;
49  };
50 
52  ros::NodeHandle& privateNh,
53  volatile bool& exiting,
54  unsigned queueSize = 5u);
55 
57 
58  void spin();
59  protected:
61  void checkInputs();
62 
63  void loadModel();
64 
65  bool validatePose(const vpHomogeneousMatrix& cMo);
66  vpHomogeneousMatrix loadInitialPose();
67  void saveInitialPose(const vpHomogeneousMatrix& cMo);
68  points_t loadInitializationPoints();
69 
70  void init();
71  void initPoint(unsigned& i,
72  points_t& points,
73  imagePoints_t& imagePoints,
74  ros::Rate& rate,
75  vpPose& pose);
76 
77 
78  void waitForImage();
79 
80  void sendcMo(const vpHomogeneousMatrix& cMo);
81 
82  std::string fetchResource(const std::string&);
83  bool makeModelFile(boost::filesystem::ofstream& modelStream,
84  const std::string& resourcePath,
85  std::string& fullModelPath);
86 
87  private:
88  bool exiting ()
89  {
90  return exiting_ || !ros::ok();
91  }
92 
93  volatile bool& exiting_;
94 
95  unsigned queueSize_;
96 
99 
101 
102  image_t image_;
103 
104  std::string modelPath_;
105  std::string modelPathAndExt_;
106  std::string modelName_;
107 
108  std::string cameraPrefix_;
109  std::string rectifiedImageTopic_;
110  std::string cameraInfoTopic_;
111  std::string trackerType_;
112  double frameSize_;
113 
114  boost::filesystem::path bModelPath_;
115  boost::filesystem::path bInitPath_;
116 
118 
119  boost::recursive_mutex mutex_;
123 
124  std_msgs::Header header_;
125  sensor_msgs::CameraInfoConstPtr info_;
126 
128  vpKltOpencv kltTracker_;
129  vpCameraParameters cameraParameters_;
130  vpMbTracker *tracker_;
131 
134 
137 
139  };
140 } // end of namespace visp_tracker.
141 
142 #endif
boost::filesystem::path bInitPath_
TrackerClient(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
void checkInputs()
Make sure the topics we subscribe already exist.
void saveInitialPose(const vpHomogeneousMatrix &cMo)
ros::NodeHandle & nodeHandle_
image_transport::ImageTransport imageTransport_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsEdgeConfig >::reconfigureSrv_t * reconfigureEdgeSrv_
ros::NodeHandle & nodeHandlePrivate_
std::vector< vpPoint > points_t
resource_retriever::Retriever resourceRetriever_
bool validatePose(const vpHomogeneousMatrix &cMo)
vpHomogeneousMatrix loadInitialPose()
vpImage< unsigned char > image_t
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
void initPoint(unsigned &i, points_t &points, imagePoints_t &imagePoints, ros::Rate &rate, vpPose &pose)
dynamic_reconfigure::Server< ConfigType > reconfigureSrv_t
ROSCPP_DECL bool ok()
image_transport::CameraSubscriber cameraSubscriber_
void sendcMo(const vpHomogeneousMatrix &cMo)
sensor_msgs::CameraInfoConstPtr info_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsConfig >::reconfigureSrv_t * reconfigureSrv_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsKltConfig >::reconfigureSrv_t * reconfigureKltSrv_
boost::filesystem::path bModelPath_
vpCameraParameters cameraParameters_
std::vector< vpImagePoint > imagePoints_t
bool makeModelFile(boost::filesystem::ofstream &modelStream, const std::string &resourcePath, std::string &fullModelPath)
boost::recursive_mutex mutex_
std::string fetchResource(const std::string &)


visp_tracker
Author(s): Thomas Moulard
autogenerated on Wed Jul 3 2019 19:48:07