BaxterInterface/asift_match/src/ROS_matcher.hpp

50 lines
1.1 KiB
C++
Raw Normal View History

2018-08-01 15:23:50 +02:00
#ifndef ROSMATCHER_HPP
#define ROSMATCHER_HPP
#include <ros/ros.h>
#include <tf/tf.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/Image.h>
#include <geometry_msgs/PointStamped.h>
#include "ASIFT_matcher.hpp"
enum MATCHER_STATUS{
MATCHER_STATUS_IDLE=0,
MATCHER_STATUS_PROCESSING,
MATCHER_STATUS_WAITING_INIT};
2018-08-01 18:05:28 +02:00
2018-08-01 15:23:50 +02:00
class ROS_matcher
{
protected:
ros::NodeHandle _nh;
//Publisher ROS
ros::Publisher _center_pub;
//Subscriber ROS
2018-08-01 18:05:28 +02:00
message_filters::Subscriber<sensor_msgs::CameraInfo>* info_sub;
message_filters::Subscriber<sensor_msgs::Image>* image_sub;
message_filters::Subscriber<sensor_msgs::PointCloud2>* pointcloud_sub;
2018-08-01 15:23:50 +02:00
//Matcher
int _num_tilt;
ASIFT_matcher matcher;
MATCHER_STATUS _status;
2018-08-01 18:05:28 +02:00
message_filters::TimeSynchronizer<sensor_msgs::CameraInfo, sensor_msgs::Image>* Timesync;
2018-08-01 15:23:50 +02:00
public:
ROS_matcher();
2018-08-01 18:05:28 +02:00
~ROS_matcher();
void cameraCallback(const sensor_msgs::CameraInfo::ConstPtr& info_msg, const sensor_msgs::Image::ConstPtr& image_msg);
2018-08-01 15:23:50 +02:00
};
#endif