ping_object_recognition_gui.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <ros/ros.h>
00031 
00032 #include <actionlib/client/simple_action_client.h>
00033 
00034 #include <sensor_msgs/Image.h>
00035 #include <sensor_msgs/CameraInfo.h>
00036 #include <sensor_msgs/PointCloud2.h>
00037 
00038 #include <stereo_msgs/DisparityImage.h>
00039 
00040 #include "object_recognition_gui/ObjectRecognitionGuiAction.h"
00041 
00042 int main(int argc, char **argv)
00043 {
00044   ros::init(argc, argv, "ping_object_recognition_gui");
00045   ros::NodeHandle nh("~");
00046   std::string topic("/object_recognition_ui");
00047 
00048   actionlib::SimpleActionClient<object_recognition_gui::ObjectRecognitionGuiAction> client(topic, true);
00049   while(!client.waitForServer(ros::Duration(2.0)) && nh.ok())
00050   {
00051     ROS_INFO("Waiting for action client on topic %s", topic.c_str());
00052   }
00053 
00054   while (nh.ok())
00055   {
00056     sensor_msgs::Image::ConstPtr recent_image;
00057     stereo_msgs::DisparityImage::ConstPtr recent_disparity_image;
00058     sensor_msgs::CameraInfo::ConstPtr recent_camera_info;
00059 
00060     ROS_INFO("Waiting for messages...");
00061     std::string image_topic("/narrow_stereo/left/image_rect");
00062     std::string disparity_image_topic("/narrow_stereo_textured/disparity");
00063     std::string camera_info_topic("/narrow_stereo_textured/left/camera_info");
00064     while ((!recent_image || !recent_disparity_image || !recent_camera_info) && nh.ok())
00065     {
00066       if (!recent_image)
00067       {
00068         ROS_INFO_STREAM("  Waiting for message on topic " << image_topic);
00069         recent_image = ros::topic::waitForMessage<sensor_msgs::Image>(image_topic, nh, ros::Duration(0.5));
00070       }
00071       if (!recent_disparity_image)
00072       {
00073         ROS_INFO_STREAM("  Waiting for message on topic " << disparity_image_topic);
00074         recent_disparity_image = ros::topic::waitForMessage<stereo_msgs::DisparityImage>
00075           (disparity_image_topic, nh, ros::Duration(0.5));
00076       }
00077       if (!recent_camera_info)
00078       {
00079         ROS_INFO_STREAM("  Waiting for message on topic " << camera_info_topic);
00080         recent_camera_info = ros::topic::waitForMessage<sensor_msgs::CameraInfo>
00081           (camera_info_topic, nh, ros::Duration(0.5));
00082       }
00083     }
00084     if (!nh.ok()) exit(0);
00085     ROS_INFO("All required messages received; sending goal to object recognition popup action");
00086 
00087     object_recognition_gui::ObjectRecognitionGuiGoal or_gui_goal;
00088     or_gui_goal.image = *recent_image;
00089     or_gui_goal.camera_info = *recent_camera_info;
00090 
00091     client.sendGoal(or_gui_goal);
00092     while (!client.waitForResult(ros::Duration(0.5)) && nh.ok())
00093     {
00094     }
00095     if (!nh.ok()) 
00096     {
00097       client.cancelGoal();
00098       break;
00099     }
00100     
00101     if (client.getState() != actionlib::SimpleClientGoalState::SUCCEEDED)
00102     {
00103       ROS_INFO("The object recognition popup action has not succeeded;");
00104     }
00105     else
00106     {    
00107       ROS_INFO("Gripper click has succeeded;");
00108     }
00109     ros::Duration(3.0).sleep();
00110   }
00111 }


object_recognition_gui
Author(s): David Gossow
autogenerated on Fri Jan 3 2014 12:01:17