#include <LaserPublisher.h>
Classes | |
struct | Impl |
Make a static class that creates these More... | |
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< Impl > | ImplPtr |
typedef boost::weak_ptr< Impl > | ImplWPtr |
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 |
Definition at line 56 of file LaserPublisher.h.
|
private |
Definition at line 100 of file LaserPublisher.h.
|
private |
Definition at line 102 of file LaserPublisher.h.
|
inline |
Definition at line 59 of file LaserPublisher.h.
|
private |
Definition at line 74 of file LaserPublisher.cpp.
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.
std::vector< std::string > laser_proc::LaserPublisher::getTopics | ( | ) | const |
Returns the topics of this LaserPublisher.
Definition at line 103 of file LaserPublisher.cpp.
laser_proc::LaserPublisher::operator void * | ( | ) | const |
Definition at line 173 of file LaserPublisher.cpp.
|
inline |
Definition at line 91 of file LaserPublisher.h.
|
inline |
Definition at line 90 of file LaserPublisher.h.
|
inline |
Definition at line 92 of file LaserPublisher.h.
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.
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.
void laser_proc::LaserPublisher::shutdown | ( | ) |
Shutdown the advertisements associated with this Publisher.
Definition at line 165 of file LaserPublisher.cpp.
|
friend |
Definition at line 106 of file LaserPublisher.h.
|
private |
Definition at line 104 of file LaserPublisher.h.