38 typedef sensor_msgs::LaserScanPtr (*
PublishFunction)(
const sensor_msgs::MultiEchoLaserScan& msg);
61 for(
size_t i = 0; i <
pubs_.size(); i++){
68 std::vector<ros::Publisher>
pubs_;
77 const ros::VoidPtr& tracked_object,
bool latch,
bool publish_echoes)
81 impl_->echo_pub_ = nh.
advertise<sensor_msgs::MultiEchoLaserScan>(
"echoes", queue_size, connect_cb, disconnect_cb, tracked_object, latch);
83 impl_->pubs_.push_back(nh.
advertise<sensor_msgs::LaserScan>(
"first", queue_size, connect_cb, disconnect_cb, tracked_object, latch));
85 impl_->pubs_.push_back(nh.
advertise<sensor_msgs::LaserScan>(
"last", queue_size, connect_cb, disconnect_cb, tracked_object, latch));
87 impl_->pubs_.push_back(nh.
advertise<sensor_msgs::LaserScan>(
"most_intense", queue_size, connect_cb, disconnect_cb, tracked_object, latch));
94 uint32_t num =
impl_->echo_pub_.getNumSubscribers();
95 for(
size_t i = 0; i <
impl_->pubs_.size(); i++){
96 num = num +
impl_->pubs_[i].getNumSubscribers();
105 std::vector<std::string> topics;
106 topics.push_back(
impl_->echo_pub_.getTopic());
108 for(
size_t i = 0; i <
impl_->pubs_.size(); i++){
109 topics.push_back(
impl_->pubs_[i].getTopic());
118 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid image_transport::LaserPublisher");
123 if(
impl_->echo_pub_){
124 if(
impl_->echo_pub_.getNumSubscribers() > 0){
125 impl_->echo_pub_.publish(msg);
130 for(
size_t i = 0; i <
impl_->pubs_.size(); i++){
131 if(
impl_->pubs_[i].getNumSubscribers() > 0){
133 impl_->pubs_[i].publish(
impl_->functs_[i](msg));
134 }
catch(std::runtime_error& e){
144 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid image_transport::LaserPublisher");
149 if(
impl_->echo_pub_){
150 impl_->echo_pub_.publish(msg);
154 for(
size_t i = 0; i <
impl_->pubs_.size(); i++){
155 if(
impl_->pubs_[i].getNumSubscribers() > 0){
157 impl_->pubs_[i].publish(
impl_->functs_[i](*msg));
158 }
catch(std::runtime_error& e){
173 LaserPublisher::operator
void*()
const 175 return (
impl_ &&
impl_->isValid()) ? (
void*)1 : (
void*)0;
static sensor_msgs::LaserScanPtr getFirstScan(const sensor_msgs::MultiEchoLaserScan &msg)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this LaserPublisher.
static sensor_msgs::LaserScanPtr getMostIntenseScan(const sensor_msgs::MultiEchoLaserScan &msg)
std::vector< std::string > getTopics() const
Returns the topics of this LaserPublisher.
Make a static class that creates these
#define ROS_ERROR_THROTTLE(rate,...)
std::vector< ros::Publisher > pubs_
#define ROS_ASSERT_MSG(cond,...)
sensor_msgs::LaserScanPtr(* PublishFunction)(const sensor_msgs::MultiEchoLaserScan &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static sensor_msgs::LaserScanPtr getLastScan(const sensor_msgs::MultiEchoLaserScan &msg)
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.
std::vector< PublishFunction > functs_