00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 #include <cstdio> 00036 #include <ros/ros.h> 00037 #include <boost/lexical_cast.hpp> 00038 #include "polled_camera/GetPolledImage.h" 00039 00040 int main(int argc, char** argv) 00041 { 00042 ros::init(argc, argv, "poller", ros::init_options::AnonymousName); 00043 if (argc < 2) { 00044 printf("Usage: %s <Hz> camera:=<namespace> output:=<namespace>\n", argv[0]); 00045 return 0; 00046 } 00047 double hz = boost::lexical_cast<double>(argv[1]); 00048 00049 ros::NodeHandle nh; 00050 std::string service_name = nh.resolveName("camera") + "/request_image"; 00051 ros::ServiceClient client = nh.serviceClient<polled_camera::GetPolledImage>(service_name); 00052 00053 polled_camera::GetPolledImage::Request req; 00054 polled_camera::GetPolledImage::Response rsp; 00055 req.response_namespace = nh.resolveName("output"); 00056 00057 ros::Rate loop_rate(hz); 00058 while (nh.ok()) { 00059 if (client.call(req, rsp)) { 00060 std::cout << "Timestamp: " << rsp.stamp << std::endl; 00061 loop_rate.sleep(); 00062 } 00063 else { 00064 ROS_ERROR("Service call failed"); 00065 client.waitForExistence(); 00066 } 00067 } 00068 }