00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
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 }