polled_camera Documentation

polled_camera

polled_camera contains a service and C++ helper classes for implementing a polled camera driver node and requesting images from it. The package is currently for internal use as the API is still under development.

NOTE: This package's API is not yet released. It may change from its current form.

polled_camera contains a service definition for requesting polled images, as well as a C++ server class to simplify publishing polled images to clients.

The protocol for polling images from a camera driver node that supports it is as follows:

  • The camera driver advertises a service call <camera>/request_image.
  • The client calls the service, specifying an output namespace in the request.
  • On receiving a request, the driver captures an image and returns its time stamp in the service response.
  • The Image and CameraInfo are published to <response_namespace>/image_raw and <response_namespace>/camera_info, latched.
  • Clients subscribe to the response topics just like any other camera image stream.

Code API

Use polled_camera::PublicationServer in camera driver nodes (or similar) to track client connections and respond to image requests.

There is not currently a matching client class, but receiving polled images is identical to subscribing to any other image topic. The only additional step is using a ros::ServiceClient to make explicit requests:

#include <ros/ros.h>
#include <polled_camera/GetPolledImage.h>
void callback(const sensor_msgs::ImageConstPtr& image, const sensor_msgs::CameraInfoConstPtr& info);
image_transport::CameraSubscriber sub = it.subscribeCamera("output_ns/image_raw", 1, callback);
ros::ServiceClient client = nh.serviceClient<polled_camera::GetPolledImage>("my_camera/request_image");
polled_camera::GetPolledImage srv;
srv.request.response_namespace = "output_ns";
if (client.call(srv))
{
ROS_INFO_STREAM("Image captured with timestamp " << srv.response.stamp);
}
image_transport::ImageTransport
ros.h
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
image_transport::CameraSubscriber
ros::ServiceClient
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
image_transport.h
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ros::NodeHandle


polled_camera
Author(s): Patrick Mihelich
autogenerated on Sat Jan 20 2024 03:14:56