Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef IMAGE_PROC_LASER_PUBLISHER_H
00035 #define IMAGE_PROC_LASER_PUBLISHER_H
00036
00037 #include <ros/ros.h>
00038
00039 #include <sensor_msgs/LaserScan.h>
00040 #include <sensor_msgs/MultiEchoLaserScan.h>
00041 #include <sensor_msgs/LaserEcho.h>
00042
00043 #include <laser_proc/LaserProc.h>
00044
00045 #include <vector>
00046 #include <algorithm>
00047 #include <limits.h>
00048 #include <stdexcept>
00049 #include <sstream>
00050
00051 namespace laser_proc
00052 {
00053
00054 class LaserTransport;
00055
00056 class LaserPublisher
00057 {
00058 public:
00059 LaserPublisher() {}
00060
00067 uint32_t getNumSubscribers() const;
00068
00072 std::vector<std::string> getTopics() const;
00073
00077 void publish(const sensor_msgs::MultiEchoLaserScan& msg) const;
00078
00082 void publish(const sensor_msgs::MultiEchoLaserScanConstPtr& msg) const;
00083
00087 void shutdown();
00088
00089 operator void*() const;
00090 bool operator< (const LaserPublisher& rhs) const { return impl_ < rhs.impl_; }
00091 bool operator!=(const LaserPublisher& rhs) const { return impl_ != rhs.impl_; }
00092 bool operator==(const LaserPublisher& rhs) const { return impl_ == rhs.impl_; }
00093
00094 private:
00095 LaserPublisher(ros::NodeHandle& nh, uint32_t queue_size,
00096 const ros::SubscriberStatusCallback& connect_cb,
00097 const ros::SubscriberStatusCallback& disconnect_cb,
00098 const ros::VoidPtr& tracked_object, bool latch, bool publish_echoes = true);
00099
00100 struct Impl;
00101 typedef boost::shared_ptr<Impl> ImplPtr;
00102 typedef boost::weak_ptr<Impl> ImplWPtr;
00103
00104 ImplPtr impl_;
00105
00106 friend class LaserTransport;
00107 };
00108
00109 };
00110
00111 #endif