40 struct CameraPublisher::Impl
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");
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;