test_find_container_action.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 *  Copyright (c) 2012, Willow Garage, Inc.
00004 *  All rights reserved.
00005 *
00006 *  Redistribution and use in source and binary forms, with or without
00007 *  modification, are permitted provided that the following conditions
00008 *  are met:
00009 *
00010 *   * Redistributions of source code must retain the above copyright
00011 *     notice, this list of conditions and the following disclaimer.
00012 *   * Redistributions in binary form must reproduce the above
00013 *     copyright notice, this list of conditions and the following
00014 *     disclaimer in the documentation and/or other materials provided
00015 *     with the distribution.
00016 *   * Neither the name of the Willow Garage nor the names of its
00017 *     contributors may be used to endorse or promote products derived
00018 *     from this software without specific prior written permission.
00019 *
00020 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 *  POSSIBILITY OF SUCH DAMAGE.
00032 *********************************************************************/
00033 
00034 // Author(s): Kaijen Hsiao
00035 
00036 #include <ros/ros.h>
00037 #include <actionlib/client/simple_action_client.h>
00038 #include <actionlib/client/terminal_state.h>
00039 #include <object_manipulation_msgs/FindContainerAction.h>
00040 
00041 #include <pcl/io/pcd_io.h>
00042 #include <pcl/point_types.h>
00043 #include <pcl_ros/transforms.h>
00044 
00045 #include <tf/transform_listener.h>
00046 
00047 int main (int argc, char **argv)
00048 {
00049   ros::init(argc, argv, "test_find_container_action");
00050 
00051   if(argc < 2)
00052   {
00053     ROS_ERROR("Usage: test_find_container_action <point_cloud_topic>");
00054     exit(-1);
00055   }
00056   tf::TransformListener tfl;
00057   ros::Duration(1.0).sleep();
00058 
00059   // create the action client
00060   // true causes the client to spin its own thread
00061   actionlib::SimpleActionClient<object_manipulation_msgs::FindContainerAction> ac("find_container_action", true);
00062 
00063   ROS_INFO("Waiting for action server to start.");
00064   // wait for the action server to start
00065   ac.waitForServer(); //will wait for infinite time
00066 
00067   sensor_msgs::PointCloud2::ConstPtr cloud = ros::topic::waitForMessage<sensor_msgs::PointCloud2>(argv[1], ros::Duration(5.0));
00068   if(!cloud)
00069   {
00070     ROS_INFO("No message received on topic %s", argv[1]);
00071     exit(-2);
00072   }
00073 
00074 
00075 
00076   ROS_INFO("Action server started, sending goal.");
00077   // send a goal to the action
00078 
00079   object_manipulation_msgs::FindContainerGoal goal;
00080 
00081 
00082   tfl.waitForTransform("/base_link", cloud->header.frame_id, cloud->header.stamp, ros::Duration(2.0));
00083   pcl_ros::transformPointCloud("/base_link", *cloud, goal.cloud, tfl);
00084 
00085   //# x: 0 - 0.5 y: -0.3 to -0.7  z: 0.22 - 0.82
00086   goal.box_pose.header.frame_id = "/base_link";
00087   goal.box_pose.pose.position.x = 0.25;
00088   goal.box_pose.pose.position.y = -0.5;
00089   goal.box_pose.pose.position.z = 0.53;
00090   goal.box_dims.x = 0.5;
00091   goal.box_dims.y = 0.4;
00092   goal.box_dims.z = 0.6;
00093 
00094 
00095 
00096   ac.sendGoal(goal);
00097 
00098   //wait for the action to return
00099   bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
00100 
00101   if (finished_before_timeout)
00102   {
00103     actionlib::SimpleClientGoalState state = ac.getState();
00104     ROS_INFO("Action finished: %s",state.toString().c_str());
00105   }
00106   else
00107     ROS_INFO("Action did not finish before the time out.");
00108 
00109   //exit
00110   return 0;
00111 }


segmented_clutter_grasp_planner
Author(s): Kaijen Hsiao
autogenerated on Mon Oct 6 2014 12:51:51