@iStarLee
2018-12-17T08:37:43.000000Z
字数 2835
阅读 443
ros
// ros_subscriber.h
#ifndef ROS_BRIDGE_ROS_SUBSCRIBER_H
#define ROS_BRIDGE_ROS_SUBSCRIBER_H
#include <ros/ros.h>
#include <std_msgs/String.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/PointCloud2.h>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <string>
using message_filters::sync_policies::ApproximateTime;
class ImageCloudSubscriber {
// typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::PointCloud2> ApproximateTimePolicy;
using ApproximateTimePolicy = message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::PointCloud2>;
public:
explicit ImageCloudSubscriber(ros::NodeHandle &nh, std::string img_topic) : m_nh(nh), m_img_topic(img_topic) {
m_img_pub = m_nh.advertise<sensor_msgs::Image>("sub_convert_image", 10);
m_img_msgpub = m_nh.advertise<sensor_msgs::Image>("msgsub_convert_image", 10);
m_cloud_msgpub = m_nh.advertise<sensor_msgs::PointCloud2>("msgsub_convert_cloud", 10);
//ros::Subscriber
m_img_sub = m_nh.subscribe(m_img_topic, 10, &ImageCloudSubscriber::callBack, this);
//message_filters::Subscriber
m_img_msgsub = new message_filters::Subscriber<sensor_msgs::Image>(m_nh, m_img_topic, 1);//equivalent with ros::Subscriber
m_img_msgsub->registerCallback(&ImageCloudSubscriber::msgFilterCallBack, this);
//message_filters::Synchronizer
m_cloud_msgsub = new message_filters::Subscriber<sensor_msgs::PointCloud2>(m_nh, "/velodyne_points", 10);
m_sync = new message_filters::Synchronizer<ApproximateTimePolicy>(ApproximateTimePolicy(100), *m_img_msgsub, *m_cloud_msgsub);
m_sync->registerCallback(boost::bind(&ImageCloudSubscriber::approximateCallback, this, _1, _2));
}
~ImageCloudSubscriber() {
delete m_img_msgsub;
delete m_cloud_msgsub;
delete m_sync;
}
private:
void callBack(const sensor_msgs::ImageConstPtr &msg) {
// m_img_pub.publish(msg);
}
void msgFilterCallBack(const sensor_msgs::ImageConstPtr &msg) {
// m_img_msgpub.publish(msg);
}
void approximateCallback(const sensor_msgs::ImageConstPtr& img, const sensor_msgs::PointCloud2ConstPtr& cloud)
{
m_img_msgpub.publish(img);
m_cloud_msgpub.publish(cloud);
}
ros::NodeHandle m_nh;
std::string m_img_topic;
ros::Subscriber m_img_sub;
message_filters::Subscriber<sensor_msgs::Image> *m_img_msgsub;//use pointer is better
message_filters::Subscriber<sensor_msgs::PointCloud2> * m_cloud_msgsub;
message_filters::Synchronizer<ApproximateTimePolicy>* m_sync;
ros::Publisher m_img_pub;
ros::Publisher m_img_msgpub;
ros::Publisher m_cloud_msgpub;
};
#endif //ROS_BRIDGE_ROS_SUBSCRIBER_H
#include <ros/ros.h>
#include "ros_subscriber.h"
int main(int argc, char **argv) {
ros::init(argc, argv, "test_node");
ros::NodeHandle nh;
ImageCloudSubscriber image_sub = ImageCloudSubscriber(nh, "/camera/image_raw");
//multi-thread
ros::AsyncSpinner spinner(1);
spinner.start();
while (ros::ok());
//single thread
//ros::spin();
return 0;
}