simple_publisher.h
Go to the documentation of this file.
1 /****************************************************************
2  ** **
3  ** Copyright(C) 2020 Quanergy Systems. All Rights Reserved. **
4  ** Contact: http://www.quanergy.com **
5  ** **
6  ****************************************************************/
7 
8 #ifndef QUANERGY_CLIENT_ROS_SIMPLE_PUBLISHER_H
9 #define QUANERGY_CLIENT_ROS_SIMPLE_PUBLISHER_H
10 
11 #include <mutex>
12 
13 #include <pcl_ros/point_cloud.h>
14 #include <pcl/point_cloud.h>
16 
17 #include <ros/ros.h>
18 #include <sensor_msgs/PointCloud2.h>
19 
21 template <typename PointT>
23 {
24 public:
25  using Cloud = pcl::PointCloud<PointT>;
26  using CloudConstPtr = typename Cloud::ConstPtr;
27 
28  SimplePublisher(ros::NodeHandle& nh, std::string topic, bool use_ros_time = false)
29  : use_ros_time_(use_ros_time)
30  {
31  topic = nh.resolveName(topic);
32  // Don't advertise too many packets.
33  // If you do, you'll create a memory leak, as these things are *huge*.
34  publisher_ = nh.advertise<pcl::PointCloud<PointT>>(topic, 10);
35  }
36 
37  void slot(const CloudConstPtr& cloud)
38  {
39  if(!ros::ok() || !cloud) return;
40 
41  sensor_msgs::PointCloud2 ros_cloud;
42  pcl::toROSMsg(*cloud, ros_cloud);
43  if (use_ros_time_)
44  {
45  ros_cloud.header.stamp = ros::Time::now();
46  }
47 
48  // don't block if publisher isn't available
49  std::unique_lock<std::timed_mutex> lock(cloud_publisher_mutex_, std::chrono::milliseconds(10));
50  if (lock)
51  {
52  publisher_.publish(ros_cloud);
53  }
54  }
55 
57  void run(double frequency = 50.)
58  {
59  ros::Rate r(frequency);
60  while (ros::ok())
61  {
63  r.sleep();
64  }
65  }
66 
67  void stop()
68  {
69  ros::shutdown();
70  }
71 
72 private:
73  std::timed_mutex cloud_publisher_mutex_;
74  bool use_ros_time_;
76 };
77 
78 
79 #endif
ros::Publisher
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
ros::shutdown
ROSCPP_DECL void shutdown()
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
point_cloud.h
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
SimplePublisher::use_ros_time_
bool use_ros_time_
Definition: simple_publisher.h:79
SimplePublisher::run
void run(double frequency=50.)
run the publisher; blocks until done
Definition: simple_publisher.h:62
SimplePublisher::Cloud
pcl::PointCloud< PointT > Cloud
Definition: simple_publisher.h:30
SimplePublisher::slot
void slot(const CloudConstPtr &cloud)
Definition: simple_publisher.h:42
SimplePublisher::stop
void stop()
Definition: simple_publisher.h:72
SimplePublisher
SimplePublisher publishes point clouds of type PointT.
Definition: simple_publisher.h:22
SimplePublisher::publisher_
ros::Publisher publisher_
Definition: simple_publisher.h:80
SimplePublisher::cloud_publisher_mutex_
std::timed_mutex cloud_publisher_mutex_
Definition: simple_publisher.h:78
SimplePublisher::SimplePublisher
SimplePublisher(ros::NodeHandle &nh, std::string topic, bool use_ros_time=false)
Definition: simple_publisher.h:33
SimplePublisher::CloudConstPtr
typename Cloud::ConstPtr CloudConstPtr
Definition: simple_publisher.h:31
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
ros::Rate
ros::NodeHandle
ros::Time::now
static Time now()
pcl_conversions.h


quanergy_client_ros
Author(s):
autogenerated on Thu May 5 2022 02:07:29