34 #ifndef IMAGE_PROC_LASER_PUBLISHER_H 35 #define IMAGE_PROC_LASER_PUBLISHER_H 39 #include <sensor_msgs/LaserScan.h> 40 #include <sensor_msgs/MultiEchoLaserScan.h> 41 #include <sensor_msgs/LaserEcho.h> 72 std::vector<std::string>
getTopics()
const;
77 void publish(
const sensor_msgs::MultiEchoLaserScan& msg)
const;
82 void publish(
const sensor_msgs::MultiEchoLaserScanConstPtr& msg)
const;
89 operator void*()
const;
98 const ros::VoidPtr& tracked_object,
bool latch,
bool publish_echoes =
true);
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this LaserPublisher.
bool operator==(const LaserPublisher &rhs) const
bool operator!=(const LaserPublisher &rhs) const
std::vector< std::string > getTopics() const
Returns the topics of this LaserPublisher.
Make a static class that creates these
boost::weak_ptr< Impl > ImplWPtr
bool operator<(const LaserPublisher &rhs) const
void shutdown()
Shutdown the advertisements associated with this Publisher.
void publish(const sensor_msgs::MultiEchoLaserScan &msg) const
Publish a MultiEchoLaserScan on the topics associated with this LaserPublisher.
boost::shared_ptr< Impl > ImplPtr