[关闭]
@iStarLee 2018-12-17T00:37:43.000000Z 字数 2835 阅读 316

ros的类内消息订阅,消息同步封装

ros


1 Subscriber code

  1. // ros_subscriber.h
  2. #ifndef ROS_BRIDGE_ROS_SUBSCRIBER_H
  3. #define ROS_BRIDGE_ROS_SUBSCRIBER_H
  4. #include <ros/ros.h>
  5. #include <std_msgs/String.h>
  6. #include <sensor_msgs/Image.h>
  7. #include <sensor_msgs/PointCloud2.h>
  8. #include <message_filters/subscriber.h>
  9. #include <message_filters/synchronizer.h>
  10. #include <message_filters/sync_policies/approximate_time.h>
  11. #include <string>
  12. using message_filters::sync_policies::ApproximateTime;
  13. class ImageCloudSubscriber {
  14. // typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::PointCloud2> ApproximateTimePolicy;
  15. using ApproximateTimePolicy = message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::PointCloud2>;
  16. public:
  17. explicit ImageCloudSubscriber(ros::NodeHandle &nh, std::string img_topic) : m_nh(nh), m_img_topic(img_topic) {
  18. m_img_pub = m_nh.advertise<sensor_msgs::Image>("sub_convert_image", 10);
  19. m_img_msgpub = m_nh.advertise<sensor_msgs::Image>("msgsub_convert_image", 10);
  20. m_cloud_msgpub = m_nh.advertise<sensor_msgs::PointCloud2>("msgsub_convert_cloud", 10);
  21. //ros::Subscriber
  22. m_img_sub = m_nh.subscribe(m_img_topic, 10, &ImageCloudSubscriber::callBack, this);
  23. //message_filters::Subscriber
  24. m_img_msgsub = new message_filters::Subscriber<sensor_msgs::Image>(m_nh, m_img_topic, 1);//equivalent with ros::Subscriber
  25. m_img_msgsub->registerCallback(&ImageCloudSubscriber::msgFilterCallBack, this);
  26. //message_filters::Synchronizer
  27. m_cloud_msgsub = new message_filters::Subscriber<sensor_msgs::PointCloud2>(m_nh, "/velodyne_points", 10);
  28. m_sync = new message_filters::Synchronizer<ApproximateTimePolicy>(ApproximateTimePolicy(100), *m_img_msgsub, *m_cloud_msgsub);
  29. m_sync->registerCallback(boost::bind(&ImageCloudSubscriber::approximateCallback, this, _1, _2));
  30. }
  31. ~ImageCloudSubscriber() {
  32. delete m_img_msgsub;
  33. delete m_cloud_msgsub;
  34. delete m_sync;
  35. }
  36. private:
  37. void callBack(const sensor_msgs::ImageConstPtr &msg) {
  38. // m_img_pub.publish(msg);
  39. }
  40. void msgFilterCallBack(const sensor_msgs::ImageConstPtr &msg) {
  41. // m_img_msgpub.publish(msg);
  42. }
  43. void approximateCallback(const sensor_msgs::ImageConstPtr& img, const sensor_msgs::PointCloud2ConstPtr& cloud)
  44. {
  45. m_img_msgpub.publish(img);
  46. m_cloud_msgpub.publish(cloud);
  47. }
  48. ros::NodeHandle m_nh;
  49. std::string m_img_topic;
  50. ros::Subscriber m_img_sub;
  51. message_filters::Subscriber<sensor_msgs::Image> *m_img_msgsub;//use pointer is better
  52. message_filters::Subscriber<sensor_msgs::PointCloud2> * m_cloud_msgsub;
  53. message_filters::Synchronizer<ApproximateTimePolicy>* m_sync;
  54. ros::Publisher m_img_pub;
  55. ros::Publisher m_img_msgpub;
  56. ros::Publisher m_cloud_msgpub;
  57. };
  58. #endif //ROS_BRIDGE_ROS_SUBSCRIBER_H

2 main.cpp code

  1. #include <ros/ros.h>
  2. #include "ros_subscriber.h"
  3. int main(int argc, char **argv) {
  4. ros::init(argc, argv, "test_node");
  5. ros::NodeHandle nh;
  6. ImageCloudSubscriber image_sub = ImageCloudSubscriber(nh, "/camera/image_raw");
  7. //multi-thread
  8. ros::AsyncSpinner spinner(1);
  9. spinner.start();
  10. while (ros::ok());
  11. //single thread
  12. //ros::spin();
  13. return 0;
  14. }
添加新批注
在作者公开此批注前,只有你和作者可见。
回复批注