73 const std::string& base_topic, uint32_t queue_size,
83 std::string image_topic = info_nh.
resolveName(base_topic);
86 impl_->image_pub_ = image_it.
advertise(image_topic, queue_size, image_connect_cb,
87 image_disconnect_cb, tracked_object, latch);
88 impl_->info_pub_ = info_nh.
advertise<sensor_msgs::CameraInfo>(info_topic, queue_size, info_connect_cb,
89 info_disconnect_cb, tracked_object, latch);
95 return std::max(
impl_->image_pub_.getNumSubscribers(),
impl_->info_pub_.getNumSubscribers());
101 if (
impl_)
return impl_->image_pub_.getTopic();
102 return std::string();
107 if (
impl_)
return impl_->info_pub_.getTopic();
108 return std::string();
114 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid image_transport::CameraPublisher");
118 impl_->image_pub_.publish(image);
119 impl_->info_pub_.publish(info);
123 const sensor_msgs::CameraInfoConstPtr& info)
const 126 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid image_transport::CameraPublisher");
130 impl_->image_pub_.publish(image);
131 impl_->info_pub_.publish(info);
138 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid image_transport::CameraPublisher");
142 image.header.stamp = stamp;
143 info.header.stamp = stamp;
155 CameraPublisher::operator
void*()
const 157 return (
impl_ &&
impl_->isValid()) ? (
void*)1 : (
void*)0;
Manages advertisements of multiple transport options on an Image topic.
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
Publish an (image, info) pair on the topics associated with this CameraPublisher. ...
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
std::string getInfoTopic() const
Returns the camera info topic of this CameraPublisher.
std::string resolveName(const std::string &name, bool remap=true) const
uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this CameraPublisher.
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise an image topic, simple version.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void shutdown()
Shutdown the advertisements associated with this Publisher.
void shutdown()
Shutdown the advertisements associated with this Publisher.
#define ROS_ASSERT_MSG(cond,...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
IMAGE_TRANSPORT_DECL std::string getCameraInfoTopic(const std::string &base_topic)
Form the camera info topic name, sibling to the base topic.
Advertise and subscribe to image topics.
std::string getTopic() const
Returns the base (image) topic of this CameraPublisher.