polled_camera Documentation

polled_camera: Library for polled camera drivers

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.

  • Homepage: http://ros.org/wiki/polled_camera
  • 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:

    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 <image_transport/image_transport.h>
    #include <polled_camera/GetPolledImage.h>
    
    void callback(const sensor_msgs::ImageConstPtr& image, const sensor_msgs::CameraInfoConstPtr& info);
    
    ros::NodeHandle nh;
    image_transport::ImageTransport it(nh);
    
    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);
    }
    
     All Classes Namespaces Files Functions Variables Typedefs Friends


    polled_camera
    Author(s): Patrick Mihelich
    autogenerated on Fri Jan 11 09:11:31 2013