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 #ifndef INTERACTIVE_MANIPULATION_BACKEND 00031 #define INTERACTIVE_MANIPULATION_BACKEND 00032 00033 #include <ros/ros.h> 00034 00035 #include <actionlib/server/simple_action_server.h> 00036 00037 #include <object_manipulator/tools/mechanism_interface.h> 00038 00039 #include <tabletop_collision_map_processing/collision_map_interface.h> 00040 00041 #include <object_manipulation_msgs/PickupAction.h> 00042 #include <object_manipulation_msgs/PlaceAction.h> 00043 00044 #include <pr2_interactive_object_detection/GraspableObjectList.h> 00045 00046 #include <pr2_create_object_model/ModelObjectInHandAction.h> 00047 #include <pr2_create_object_model/ObjectInHand.h> 00048 00049 #include "pr2_interactive_manipulation/gripper_controller.h" 00050 00051 #include "pr2_interactive_manipulation/IMGUIOptions.h" 00052 #include "pr2_interactive_manipulation/IMGUIAdvancedOptions.h" 00053 #include "pr2_interactive_manipulation/IMGUICommand.h" 00054 #include "pr2_interactive_manipulation/IMGUIAction.h" 00055 00056 #include <sensor_msgs/PointCloud2.h> 00057 00058 namespace pr2_interactive_manipulation { 00059 00060 class InteractiveManipulationBackend 00061 { 00062 00063 public: 00064 InteractiveManipulationBackend(); 00065 ~InteractiveManipulationBackend(); 00066 00067 private: 00068 struct GraspInfo 00069 { 00070 static geometry_msgs::Pose verticalGripper() 00071 { 00072 geometry_msgs::Pose pose; 00073 pose.position.x = 0; 00074 pose.position.y = 0; 00075 pose.position.z = 0.2; 00076 pose.orientation.x = 0; 00077 pose.orientation.y = sqrt(0.5); 00078 pose.orientation.z = 0; 00079 pose.orientation.w = sqrt(0.5); 00080 return pose; 00081 } 00082 static geometry_msgs::Pose identityPose() 00083 { 00084 geometry_msgs::Pose pose; 00085 pose.position.x = pose.position.y = pose.position.z = 0.0; 00086 pose.orientation = identityQuaternion(); 00087 return pose; 00088 } 00089 static geometry_msgs::Quaternion identityQuaternion() 00090 { 00091 geometry_msgs::Quaternion q; 00092 q.x = q.y = q.z = 0.0; 00093 q.w = 1.0; 00094 return q; 00095 } 00096 00097 GraspInfo() 00098 { 00099 grasp_.grasp_pose = verticalGripper(); 00100 object_.reference_frame_id = "base_link"; 00101 object_orientation_ = identityQuaternion(); 00102 } 00103 std::string object_collision_name_; 00104 object_manipulation_msgs::GraspableObject object_; 00105 object_manipulation_msgs::Grasp grasp_; 00106 geometry_msgs::Quaternion object_orientation_; 00107 }; 00108 00109 GraspInfo* getGraspInfo(std::string arm_name) 00110 { 00111 if (arm_name=="right_arm") return &grasp_info_right_; 00112 return &grasp_info_left_; 00113 } 00114 00115 void graspableObjectsCallback(const pr2_interactive_object_detection::GraspableObjectListConstPtr &objects); 00116 00117 bool interruptRequested(); 00118 00119 void setStatusLabel(std::string text); 00120 00121 bool processCollisionMapForPickup(const IMGUIOptions &options, object_manipulation_msgs::PickupGoal &goal); 00122 00123 //pick up (grasp) an object. 00124 //if the object parameter is omitted, will call Gripper Click Pickup 00125 //otherwise will try to pick up the given object autonomously 00126 int pickupObject(const IMGUIOptions &options, 00127 object_manipulation_msgs::GraspableObject object = object_manipulation_msgs::GraspableObject() ); 00128 00129 int placeObject(const IMGUIOptions &options); 00130 00131 void takeMap(); 00132 00133 void collisionReset(int reset_choice); 00134 00135 void lookAtTable(); 00136 00137 void armMotion(int arm_selection_choice, int arm_action_choice, 00138 int arm_planner_choice, bool collision, object_manipulation_msgs::ManipulationResult &result); 00139 00140 void moveGripper(IMGUIOptions options); 00141 00142 int modelObject(IMGUIOptions options); 00143 00144 void actionCallback(const IMGUIGoalConstPtr &goal); 00145 00146 int callGripperClickPickup( std::string arm_name, std::vector<object_manipulation_msgs::Grasp> &grasps ); 00147 00148 ros::ServiceClient grasp_planning_srv_; 00149 ros::ServiceClient place_planning_srv_; 00150 ros::ServiceClient get_model_description_srv_; 00151 ros::Subscriber graspable_objects_sub_; 00152 actionlib::SimpleActionServer<IMGUIAction> *action_server_; 00153 00154 ros::NodeHandle root_nh_; 00155 00156 ros::NodeHandle priv_nh_; 00157 00158 GripperController gripper_controller_; 00159 00160 std::string grasp_planning_service_name_; 00161 std::string place_planning_service_name_; 00162 std::string pickup_action_name_; 00163 std::string place_action_name_; 00164 std::string create_model_action_name_; 00165 std::string action_name_; 00166 00167 tabletop_collision_map_processing::CollisionMapInterface collision_map_interface_; 00168 00169 object_manipulator::MechanismInterface mech_interface_; 00170 00171 actionlib::SimpleActionClient<object_manipulation_msgs::PickupAction> *pickup_client_; 00172 actionlib::SimpleActionClient<object_manipulation_msgs::PlaceAction> *place_client_; 00173 00174 actionlib::SimpleActionClient<pr2_create_object_model::ModelObjectInHandAction> *create_model_client_; 00175 00176 std::vector<object_manipulation_msgs::GraspableObject> graspable_objects_; 00177 00178 pr2_interactive_object_detection::GraspableObjectListConstPtr received_objects_; 00179 boost::mutex received_objects_mutex_; 00180 00181 bool new_object_list_; 00182 00183 // std::map< std::String, GraspInfo > pickup_grasp_info_; 00184 00185 GraspInfo grasp_info_right_; 00186 GraspInfo grasp_info_left_; 00187 00188 sensor_msgs::PointCloud2 object_model_left_; 00189 sensor_msgs::PointCloud2 object_model_right_; 00190 }; 00191 00192 } 00193 00194 #endif