Ajout d'options au launch file

Reste a regler le problème de queue ROS -> lent ...
This commit is contained in:
Unknown 2018-08-03 14:57:20 +02:00
parent 3a7050eb53
commit ced3ccd8cd
5 changed files with 23 additions and 14 deletions

View file

@ -19,7 +19,7 @@
#include "ASIFT_matcher.hpp"
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::PointCloud2> MySyncPolicy;
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::PointCloud2> MySyncPolicy;
enum MATCHER_STATUS{
MATCHER_STATUS_IDLE=0,
@ -36,7 +36,7 @@ protected:
ros::Publisher _center_pub;
//Subscriber ROS
message_filters::Subscriber<sensor_msgs::CameraInfo>* info_sub;
// message_filters::Subscriber<sensor_msgs::CameraInfo>* info_sub;
message_filters::Subscriber<sensor_msgs::Image>* image_sub;
message_filters::Subscriber<sensor_msgs::PointCloud2>* pointcloud_sub;
@ -48,10 +48,12 @@ protected:
message_filters::Synchronizer<MySyncPolicy>* Timesync;
std::string tracked_object;
public:
ROS_matcher();
~ROS_matcher();
void cameraCallback(const sensor_msgs::CameraInfo::ConstPtr& info_msg, const sensor_msgs::Image::ConstPtr& image_msg, const sensor_msgs::PointCloud2::ConstPtr& pointcloud_msg);
void cameraCallback(const sensor_msgs::Image::ConstPtr& image_msg, const sensor_msgs::PointCloud2::ConstPtr& pointcloud_msg);
};
#endif