42 class PublicationServer::Impl
49 std::map<std::string, image_transport::CameraPublisher> client_map_;
56 constructed_(
ros::WallTime::now().toSec())
63 ROS_WARN(
"PublicationServer destroyed immediately after creation. Did you forget to store the handle?");
69 return !unadvertised_;
81 bool requestCallback(polled_camera::GetPolledImage::Request& req,
82 polled_camera::GetPolledImage::Response& rsp)
84 std::string image_topic = req.response_namespace +
"/image_raw";
89 boost::bind(&Impl::disconnectCallback,
this, boost::placeholders::_1),
96 req.binning_x = std::max(req.binning_x, (uint32_t)1);
97 req.binning_y = std::max(req.binning_y, (uint32_t)1);
100 sensor_msgs::Image image;
101 sensor_msgs::CameraInfo info;
102 driver_cb_(req, rsp, image, info);
105 assert(image.header.stamp == info.header.stamp);
106 rsp.stamp = image.header.stamp;
110 ROS_ERROR(
"Failed to capture requested image, status message: '%s'",
111 rsp.status_message.c_str());
130 const DriverCallback& cb,
const ros::VoidPtr& tracked_object)
131 : impl_(new Impl(nh))
133 impl_->driver_cb_ = cb;
134 impl_->tracked_object_ = tracked_object;
135 impl_->srv_server_ = nh.
advertiseService<>(service, &Impl::requestCallback, impl_);
138 void PublicationServer::shutdown()
140 if (impl_) impl_->unadvertise();
143 std::string PublicationServer::getService()
const
145 if (impl_)
return impl_->srv_server_.
getService();
146 return std::string();
149 PublicationServer::operator
void*()
const
151 return (impl_ && impl_->isValid()) ? (
void*)1 : (
void*)0;
155 const PublicationServer::DriverCallback& cb,
158 return PublicationServer(service, nh, cb, tracked_object);