node.h
Go to the documentation of this file.
1 #ifndef __VISP_AUTO_TRACKER_NODE_H__
2 #define __VISP_AUTO_TRACKER_NODE_H__
3 #include "ros/ros.h"
4 
5 #include "visp/vpConfig.h"
7 #include <string>
8 
11 #include "sensor_msgs/CameraInfo.h"
12 #include "sensor_msgs/Image.h"
13 #include "geometry_msgs/PoseStamped.h"
14 #include "geometry_msgs/PoseWithCovarianceStamped.h"
15 #include "std_msgs/Header.h"
16 #include <sstream>
17 
18 namespace visp_auto_tracker{
19  class Node{
20  private:
21  boost::mutex lock_;
23  unsigned long queue_size_;
24  std::string tracker_config_path_;
25  std::string model_description_;
26  std::string model_path_;
27  std::string model_name_;
28  std::string code_message_;
30 
31  vpImage<vpRGBa> I_; // Image used for debug display
32  std_msgs::Header image_header_;
33  bool got_image_;
34  vpCameraParameters cam_;
35 
38 
39  void waitForImage();
40 
41  void frameCallback(const sensor_msgs::ImageConstPtr& image, const sensor_msgs::CameraInfoConstPtr& cam_info);
42 
43  public:
44  Node();
45  void spin();
46  };
47 };
48 #endif
std::string tracker_config_path_
Definition: node.h:24
tracking::Tracker * t_
Definition: node.h:36
msm::back::state_machine< Tracker_ > Tracker
Definition: tracking.h:186
ros::NodeHandle n_
Definition: node.h:22
std::string model_name_
Definition: node.h:27
vpCameraParameters cam_
Definition: node.h:34
std::string code_message_
Definition: node.h:28
std::string model_path_
Definition: node.h:26
boost::mutex lock_
Definition: node.h:21
vpImage< vpRGBa > I_
Definition: node.h:31
std::string model_description_
Definition: node.h:25
unsigned long queue_size_
Definition: node.h:23
std_msgs::Header image_header_
Definition: node.h:32
void frameCallback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::CameraInfoConstPtr &cam_info)
Definition: node.cpp:105


visp_auto_tracker
Author(s): Filip Novotny
autogenerated on Wed Jul 3 2019 19:48:10