ping_object_segmentation_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_segmentation_gui/ObjectSegmentationGuiAction.h"
00041 
00042 
00043 int main(int argc, char **argv)
00044 {
00045   ros::init(argc, argv, "ping_object_segmentation_gui");
00046   ros::NodeHandle nh("~");
00047   std::string topic("/segmentation_popup");
00048 
00049   actionlib::SimpleActionClient<object_segmentation_gui::ObjectSegmentationGuiAction> client(topic, true);
00050   while(!client.waitForServer(ros::Duration(2.0)) && nh.ok())
00051   {
00052     ROS_INFO("Waiting for action client on topic %s", topic.c_str());
00053   }
00054 
00055   while (nh.ok())
00056   {
00057     sensor_msgs::Image::ConstPtr recent_image;
00058     stereo_msgs::DisparityImage::ConstPtr recent_disparity_image;
00059     sensor_msgs::CameraInfo::ConstPtr recent_camera_info;
00060     sensor_msgs::Image::ConstPtr recent_wide_image;
00061     sensor_msgs::CameraInfo::ConstPtr recent_wide_camera_info;
00062 
00063     ROS_INFO("Waiting for messages...");
00064     std::string image_topic("/narrow_stereo/left/image_rect");
00065     std::string disparity_image_topic("/narrow_stereo_textured/disparity");
00066     std::string camera_info_topic("/narrow_stereo_textured/left/camera_info");
00067     std::string wide_camera_info_topic("/wide_stereo/left/camera_info");
00068     std::string wide_image_topic("/wide_stereo/left/image_rect_color");
00069     while ((!recent_image || !recent_disparity_image || !recent_camera_info 
00070             || !recent_wide_image || !recent_wide_camera_info) && nh.ok())
00071     {
00072       if (!recent_image)
00073       {
00074         ROS_INFO_STREAM("  Waiting for message on topic " << image_topic);
00075         recent_image = ros::topic::waitForMessage<sensor_msgs::Image>(image_topic, nh, ros::Duration(0.5));
00076       }
00077       if (!recent_disparity_image)
00078       {
00079         ROS_INFO_STREAM("  Waiting for message on topic " << disparity_image_topic);
00080         recent_disparity_image = ros::topic::waitForMessage<stereo_msgs::DisparityImage>
00081           (disparity_image_topic, nh, ros::Duration(0.5));
00082       }
00083       if (!recent_camera_info)
00084       {
00085         ROS_INFO_STREAM("  Waiting for message on topic " << camera_info_topic);
00086         recent_camera_info = ros::topic::waitForMessage<sensor_msgs::CameraInfo>
00087           (camera_info_topic, nh, ros::Duration(0.5));
00088       }
00089       if (!recent_wide_camera_info)
00090         {
00091           ROS_INFO_STREAM("  Waiting for message on topic " << wide_camera_info_topic);
00092           recent_wide_camera_info = ros::topic::waitForMessage<sensor_msgs::CameraInfo>
00093             (wide_camera_info_topic, nh, ros::Duration(0.5));
00094         }
00095       if (!recent_wide_image)
00096       {
00097         ROS_INFO_STREAM("  Waiting for message on topic " << wide_image_topic);
00098         recent_wide_image = ros::topic::waitForMessage<sensor_msgs::Image>(wide_image_topic, nh, ros::Duration(0.5));
00099       }
00100     }
00101     if (!nh.ok()) exit(0);
00102     ROS_INFO("All required messages received; sending goal to gripper click action");
00103     
00104     object_segmentation_gui::ObjectSegmentationGuiGoal os_gui_goal;
00105     os_gui_goal.image = *recent_image;
00106     os_gui_goal.disparity_image = *recent_disparity_image;
00107     os_gui_goal.camera_info = *recent_camera_info;
00108     os_gui_goal.wide_field = *recent_wide_image;
00109     os_gui_goal.wide_camera_info = *recent_wide_camera_info;
00110 
00111     client.sendGoal(os_gui_goal);
00112     while (!client.waitForResult(ros::Duration(0.5)) && nh.ok())
00113     {
00114     }
00115     if (!nh.ok()) 
00116     {
00117       client.cancelGoal();
00118       break;
00119     }
00120     
00121     if (client.getState() != actionlib::SimpleClientGoalState::SUCCEEDED)
00122       {
00123       ROS_INFO("The object segmentation action has not succeeded;");
00124     }
00125     else
00126     {    
00127       ROS_INFO("Object Segmentation has succeeded;");
00128     }
00129     ros::Duration(3.0).sleep();
00130   }
00131 }


object_segmentation_gui
Author(s): Jeannette Bohg
autogenerated on Fri Jan 3 2014 12:03:36