18 #ifndef MARKER_TRACKING_NODE_MARKER_TRACKER_H_
19 #define MARKER_TRACKING_NODE_MARKER_TRACKER_H_
25 #include <ff_msgs/SetBool.h>
26 #include <ff_msgs/VisualLandmarks.h>
28 #include <image_transport/image_transport.h>
29 #include <ros/publisher.h>
37 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
38 explicit MarkerTracker(ros::NodeHandle* nh, ros::NodeHandle* private_nh,
39 const std::string& nm);
42 void PublishVO(
struct timeval
const& timestamp);
45 void VideoCallback(
const sensor_msgs::ImageConstPtr& image_msg);
46 bool EnableService(ff_msgs::SetBool::Request& req,
47 ff_msgs::SetBool::Response& res);
48 void ReadParams(
void);
49 int EstimatePose(ff_msgs::VisualLandmarks* msg);
50 bool IsMarkerValid(
const alvar::MarkerData & marker);
53 ros::Timer config_timer_;
55 image_transport::ImageTransport it_;
56 image_transport::Subscriber image_sub_;
57 ros::ServiceServer enable_srv_;
58 ros::Publisher landmark_publisher_, reg_publisher_;
61 const std::string& nodelet_name_;
63 std::shared_ptr<marker_tracking::MarkerCornerDetector> detector_;
70 #endif // MARKER_TRACKING_NODE_MARKER_TRACKER_H_