Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | Friends | List of all members
laser_proc::LaserPublisher Class Reference

#include <LaserPublisher.h>

Classes

struct  Impl
 

Public Member Functions

uint32_t getNumSubscribers () const
 Returns the number of subscribers that are currently connected to this LaserPublisher. More...
 
std::vector< std::string > getTopics () const
 Returns the topics of this LaserPublisher. More...
 
 LaserPublisher ()
 
 operator void * () const
 
bool operator!= (const LaserPublisher &rhs) const
 
bool operator< (const LaserPublisher &rhs) const
 
bool operator== (const LaserPublisher &rhs) const
 
void publish (const sensor_msgs::MultiEchoLaserScan &msg) const
 Publish a MultiEchoLaserScan on the topics associated with this LaserPublisher. More...
 
void publish (const sensor_msgs::MultiEchoLaserScanConstPtr &msg) const
 Publish a MultiEchoLaserScan on the topics associated with this LaserPublisher. More...
 
void shutdown ()
 Shutdown the advertisements associated with this Publisher. More...
 

Private Types

typedef boost::shared_ptr< ImplImplPtr
 
typedef boost::weak_ptr< ImplImplWPtr
 

Private Member Functions

 LaserPublisher (ros::NodeHandle &nh, uint32_t queue_size, const ros::SubscriberStatusCallback &connect_cb, const ros::SubscriberStatusCallback &disconnect_cb, const ros::VoidPtr &tracked_object, bool latch, bool publish_echoes=true)
 

Private Attributes

ImplPtr impl_
 

Friends

class LaserTransport
 

Detailed Description

Definition at line 56 of file LaserPublisher.h.

Member Typedef Documentation

◆ ImplPtr

Definition at line 100 of file LaserPublisher.h.

◆ ImplWPtr

typedef boost::weak_ptr<Impl> laser_proc::LaserPublisher::ImplWPtr
private

Definition at line 102 of file LaserPublisher.h.

Constructor & Destructor Documentation

◆ LaserPublisher() [1/2]

laser_proc::LaserPublisher::LaserPublisher ( )
inline

Definition at line 59 of file LaserPublisher.h.

◆ LaserPublisher() [2/2]

laser_proc::LaserPublisher::LaserPublisher ( ros::NodeHandle nh,
uint32_t  queue_size,
const ros::SubscriberStatusCallback connect_cb,
const ros::SubscriberStatusCallback disconnect_cb,
const ros::VoidPtr tracked_object,
bool  latch,
bool  publish_echoes = true 
)
private

Definition at line 74 of file LaserPublisher.cpp.

Member Function Documentation

◆ getNumSubscribers()

uint32_t laser_proc::LaserPublisher::getNumSubscribers ( ) const

Returns the number of subscribers that are currently connected to this LaserPublisher.

Returns sum of all child publishers.

Definition at line 91 of file LaserPublisher.cpp.

◆ getTopics()

std::vector< std::string > laser_proc::LaserPublisher::getTopics ( ) const

Returns the topics of this LaserPublisher.

Definition at line 103 of file LaserPublisher.cpp.

◆ operator void *()

laser_proc::LaserPublisher::operator void * ( ) const

Definition at line 173 of file LaserPublisher.cpp.

◆ operator!=()

bool laser_proc::LaserPublisher::operator!= ( const LaserPublisher rhs) const
inline

Definition at line 91 of file LaserPublisher.h.

◆ operator<()

bool laser_proc::LaserPublisher::operator< ( const LaserPublisher rhs) const
inline

Definition at line 90 of file LaserPublisher.h.

◆ operator==()

bool laser_proc::LaserPublisher::operator== ( const LaserPublisher rhs) const
inline

Definition at line 92 of file LaserPublisher.h.

◆ publish() [1/2]

void laser_proc::LaserPublisher::publish ( const sensor_msgs::MultiEchoLaserScan &  msg) const

Publish a MultiEchoLaserScan on the topics associated with this LaserPublisher.

Definition at line 115 of file LaserPublisher.cpp.

◆ publish() [2/2]

void laser_proc::LaserPublisher::publish ( const sensor_msgs::MultiEchoLaserScanConstPtr &  msg) const

Publish a MultiEchoLaserScan on the topics associated with this LaserPublisher.

Definition at line 141 of file LaserPublisher.cpp.

◆ shutdown()

void laser_proc::LaserPublisher::shutdown ( )

Shutdown the advertisements associated with this Publisher.

Definition at line 165 of file LaserPublisher.cpp.

Friends And Related Function Documentation

◆ LaserTransport

friend class LaserTransport
friend

Definition at line 106 of file LaserPublisher.h.

Member Data Documentation

◆ impl_

ImplPtr laser_proc::LaserPublisher::impl_
private

Definition at line 104 of file LaserPublisher.h.


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


laser_proc
Author(s): Chad Rockey
autogenerated on Wed Mar 2 2022 00:27:34