Public Types | Public Member Functions | Private Attributes | List of all members
SimplePublisher< PointT > Class Template Reference

SimplePublisher publishes point clouds of type PointT. More...

#include <simple_publisher.h>

Public Types

using Cloud = pcl::PointCloud< PointT >
 
using CloudConstPtr = typename Cloud::ConstPtr
 

Public Member Functions

void run (double frequency=50.)
 run the publisher; blocks until done More...
 
 SimplePublisher (ros::NodeHandle &nh, std::string topic, bool use_ros_time=false)
 
void slot (const CloudConstPtr &cloud)
 
void stop ()
 

Private Attributes

std::timed_mutex cloud_publisher_mutex_
 
ros::Publisher publisher_
 
bool use_ros_time_
 

Detailed Description

template<typename PointT>
class SimplePublisher< PointT >

SimplePublisher publishes point clouds of type PointT.

Definition at line 22 of file simple_publisher.h.

Member Typedef Documentation

◆ Cloud

template<typename PointT >
using SimplePublisher< PointT >::Cloud = pcl::PointCloud<PointT>

Definition at line 30 of file simple_publisher.h.

◆ CloudConstPtr

template<typename PointT >
using SimplePublisher< PointT >::CloudConstPtr = typename Cloud::ConstPtr

Definition at line 31 of file simple_publisher.h.

Constructor & Destructor Documentation

◆ SimplePublisher()

template<typename PointT >
SimplePublisher< PointT >::SimplePublisher ( ros::NodeHandle nh,
std::string  topic,
bool  use_ros_time = false 
)
inline

Definition at line 33 of file simple_publisher.h.

Member Function Documentation

◆ run()

template<typename PointT >
void SimplePublisher< PointT >::run ( double  frequency = 50.)
inline

run the publisher; blocks until done

Definition at line 62 of file simple_publisher.h.

◆ slot()

template<typename PointT >
void SimplePublisher< PointT >::slot ( const CloudConstPtr cloud)
inline

Definition at line 42 of file simple_publisher.h.

◆ stop()

template<typename PointT >
void SimplePublisher< PointT >::stop ( )
inline

Definition at line 72 of file simple_publisher.h.

Member Data Documentation

◆ cloud_publisher_mutex_

template<typename PointT >
std::timed_mutex SimplePublisher< PointT >::cloud_publisher_mutex_
private

Definition at line 78 of file simple_publisher.h.

◆ publisher_

template<typename PointT >
ros::Publisher SimplePublisher< PointT >::publisher_
private

Definition at line 80 of file simple_publisher.h.

◆ use_ros_time_

template<typename PointT >
bool SimplePublisher< PointT >::use_ros_time_
private

Definition at line 79 of file simple_publisher.h.


The documentation for this class was generated from the following file:


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