Class LaserPublisher
Defined in File laser_publisher.hpp
Class Documentation
-
class LaserPublisher
Public Functions
- LASER_PROC_PUBLIC size_t getNumSubscribers () const
Returns the number of subscribers that are currently connected to this LaserPublisher.
Returns sum of all child publishers.
- LASER_PROC_PUBLIC std::vector< std::string > getTopics () const
Returns the topics of this LaserPublisher.
- LASER_PROC_PUBLIC void publish (const sensor_msgs::msg::MultiEchoLaserScan &msg) const
Publish a MultiEchoLaserScan on the topics associated with this LaserPublisher.
- LASER_PROC_PUBLIC void publish (sensor_msgs::msg::MultiEchoLaserScan::ConstSharedPtr msg) const
Publish a MultiEchoLaserScan on the topics associated with this LaserPublisher.
- LASER_PROC_PUBLIC void shutdown ()
Shutdown the advertisements associated with this Publisher.
-
LASER_PROC_PUBLIC operator void*() const
- inline LASER_PROC_PUBLIC bool operator< (const LaserPublisher &rhs) const
- inline LASER_PROC_PUBLIC bool operator!= (const LaserPublisher &rhs) const
- inline LASER_PROC_PUBLIC bool operator== (const LaserPublisher &rhs) const