$search
00001 #include <ros/ros.h> 00002 #include <actionlib/client/simple_action_client.h> 00003 #include <actionlib/client/terminal_state.h> 00004 #include <object_manipulation_msgs/FindContainerAction.h> 00005 00006 #include <pcl/io/pcd_io.h> 00007 #include <pcl/point_types.h> 00008 #include <pcl_ros/transforms.h> 00009 00010 #include <tf/transform_listener.h> 00011 00012 int main (int argc, char **argv) 00013 { 00014 ros::init(argc, argv, "test_find_container_action"); 00015 00016 if(argc < 2) 00017 { 00018 ROS_ERROR("Usage: test_find_container_action <point_cloud_topic>"); 00019 exit(-1); 00020 } 00021 tf::TransformListener tfl; 00022 ros::Duration(1.0).sleep(); 00023 00024 // create the action client 00025 // true causes the client to spin its own thread 00026 actionlib::SimpleActionClient<object_manipulation_msgs::FindContainerAction> ac("find_container_action", true); 00027 00028 ROS_INFO("Waiting for action server to start."); 00029 // wait for the action server to start 00030 ac.waitForServer(); //will wait for infinite time 00031 00032 sensor_msgs::PointCloud2::ConstPtr cloud = ros::topic::waitForMessage<sensor_msgs::PointCloud2>(argv[1], ros::Duration(5.0)); 00033 if(!cloud) 00034 { 00035 ROS_INFO("No message received on topic %s", argv[1]); 00036 exit(-2); 00037 } 00038 00039 00040 00041 ROS_INFO("Action server started, sending goal."); 00042 // send a goal to the action 00043 00044 object_manipulation_msgs::FindContainerGoal goal; 00045 00046 00047 tfl.waitForTransform("/base_link", cloud->header.frame_id, cloud->header.stamp, ros::Duration(2.0)); 00048 pcl_ros::transformPointCloud("/base_link", *cloud, goal.cloud, tfl); 00049 00050 //# x: 0 - 0.5 y: -0.3 to -0.7 z: 0.22 - 0.82 00051 goal.box_pose.header.frame_id = "/base_link"; 00052 goal.box_pose.pose.position.x = 0.25; 00053 goal.box_pose.pose.position.y = -0.5; 00054 goal.box_pose.pose.position.z = 0.53; 00055 goal.box_dims.x = 0.5; 00056 goal.box_dims.y = 0.4; 00057 goal.box_dims.z = 0.6; 00058 00059 00060 00061 ac.sendGoal(goal); 00062 00063 //wait for the action to return 00064 bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0)); 00065 00066 if (finished_before_timeout) 00067 { 00068 actionlib::SimpleClientGoalState state = ac.getState(); 00069 ROS_INFO("Action finished: %s",state.toString().c_str()); 00070 } 00071 else 00072 ROS_INFO("Action did not finish before the time out."); 00073 00074 //exit 00075 return 0; 00076 }