2018-08-08 15:45:19 +02:00
|
|
|
/*
|
|
|
|
* ROS wrapper for the ASIFT_matcher object.
|
|
|
|
* Track an object described in the references in a RGBD stream and publish it's center.
|
|
|
|
* @author : antoine.harle@etu.upmc.Fr
|
|
|
|
* @see : ASIFT_matcher.cpp/.hpp, asift_match.launch
|
|
|
|
*/
|
|
|
|
|
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>
|
2018-08-02 11:31:09 +02:00
|
|
|
#include <message_filters/synchronizer.h>
|
|
|
|
#include <message_filters/sync_policies/approximate_time.h>
|
2018-08-01 15:23:50 +02:00
|
|
|
|
|
|
|
#include <sensor_msgs/CameraInfo.h>
|
|
|
|
#include <sensor_msgs/PointCloud2.h>
|
|
|
|
#include <sensor_msgs/Image.h>
|
|
|
|
#include <geometry_msgs/PointStamped.h>
|
2018-08-02 17:06:53 +02:00
|
|
|
#include <rviz_interface/NamedPoint.h>
|
2018-08-01 15:23:50 +02:00
|
|
|
|
2018-08-02 11:31:09 +02:00
|
|
|
#include <pcl_conversions/pcl_conversions.h>
|
2018-08-02 17:06:53 +02:00
|
|
|
#include <pcl/impl/point_types.hpp>
|
2018-08-02 11:31:09 +02:00
|
|
|
|
2018-08-01 15:23:50 +02:00
|
|
|
#include "ASIFT_matcher.hpp"
|
|
|
|
|
2018-08-03 14:57:20 +02:00
|
|
|
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::PointCloud2> MySyncPolicy;
|
2018-08-02 11:31:09 +02:00
|
|
|
|
2018-08-01 15:23:50 +02:00
|
|
|
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-03 14:57:20 +02:00
|
|
|
// message_filters::Subscriber<sensor_msgs::CameraInfo>* info_sub;
|
2018-08-03 17:14:26 +02:00
|
|
|
message_filters::Subscriber<sensor_msgs::Image>* _image_sub;
|
|
|
|
message_filters::Subscriber<sensor_msgs::PointCloud2>* _pointcloud_sub;
|
2018-08-08 15:45:19 +02:00
|
|
|
|
|
|
|
message_filters::Synchronizer<MySyncPolicy>* Timesync;
|
2018-08-01 15:23:50 +02:00
|
|
|
|
|
|
|
//Matcher
|
2018-08-10 16:57:26 +02:00
|
|
|
int _num_tilt; //Number of tilts
|
|
|
|
float _filter_coeff; //Filter parameter
|
2018-08-08 15:45:19 +02:00
|
|
|
ASIFT_matcher matcher; //Matcher
|
2018-08-01 15:23:50 +02:00
|
|
|
|
2018-08-08 15:45:19 +02:00
|
|
|
MATCHER_STATUS _status; //Matcher status
|
2018-08-01 18:05:28 +02:00
|
|
|
|
2018-08-08 15:45:19 +02:00
|
|
|
std::string tracked_object; //Name of the tracked object.
|
2018-08-03 14:57:20 +02:00
|
|
|
|
2018-08-01 15:23:50 +02:00
|
|
|
public:
|
|
|
|
ROS_matcher();
|
2018-08-01 18:05:28 +02:00
|
|
|
~ROS_matcher();
|
2018-08-03 14:57:20 +02:00
|
|
|
void cameraCallback(const sensor_msgs::Image::ConstPtr& image_msg, const sensor_msgs::PointCloud2::ConstPtr& pointcloud_msg);
|
2018-08-01 15:23:50 +02:00
|
|
|
|
|
|
|
};
|
|
|
|
#endif
|