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 #ifndef INTERACTIVE_MANIPULATION_BACKEND
00031 #define INTERACTIVE_MANIPULATION_BACKEND
00032
00033 #include <boost/thread/mutex.hpp>
00034
00035 #include <stdexcept>
00036
00037 #include <ros/ros.h>
00038
00039 #include <actionlib/server/simple_action_server.h>
00040
00041 #include <tf/transform_listener.h>
00042
00043 #include <sensor_msgs/PointCloud2.h>
00044
00045 #include <std_srvs/Empty.h>
00046
00047 #include <object_manipulator/tools/mechanism_interface.h>
00048 #include <object_manipulator/tools/hand_description.h>
00049 #include <object_manipulator/tools/service_action_wrappers.h>
00050
00051 #include <tabletop_collision_map_processing/collision_map_interface.h>
00052
00053 #include <object_manipulation_msgs/PickupAction.h>
00054 #include <object_manipulation_msgs/PlaceAction.h>
00055
00056 #include <pr2_create_object_model/ModelObjectInHandAction.h>
00057 #include <pr2_create_object_model/ObjectInHand.h>
00058
00059 #include <pr2_object_manipulation_msgs/GetGripperPoseAction.h>
00060 #include <pr2_object_manipulation_msgs/TestGripperPoseAction.h>
00061
00062 #include "pr2_interactive_manipulation/gripper_controller.h"
00063
00064 #include "pr2_object_manipulation_msgs/IMGUIOptions.h"
00065 #include "pr2_object_manipulation_msgs/IMGUIAdvancedOptions.h"
00066 #include "pr2_object_manipulation_msgs/IMGUICommand.h"
00067 #include "pr2_object_manipulation_msgs/IMGUIAction.h"
00068 #include "pr2_object_manipulation_msgs/ImageClick.h"
00069 #include "pr2_object_manipulation_msgs/RunScriptAction.h"
00070
00071 #include "move_base_msgs/MoveBaseAction.h"
00072
00073 namespace pr2_interactive_manipulation {
00074
00075 class InteractiveManipulationBackend
00076 {
00077
00078 public:
00079 InteractiveManipulationBackend();
00080 ~InteractiveManipulationBackend();
00081
00082 private:
00083
00084 struct GraspInfo
00085 {
00086 static geometry_msgs::Pose verticalGripper()
00087 {
00088 geometry_msgs::Pose pose;
00089 pose.position.x = 0;
00090 pose.position.y = 0;
00091 pose.position.z = 0.2;
00092 pose.orientation.x = 0;
00093 pose.orientation.y = sqrt(0.5);
00094 pose.orientation.z = 0;
00095 pose.orientation.w = sqrt(0.5);
00096 return pose;
00097 }
00098 static geometry_msgs::Pose identityPose()
00099 {
00100 geometry_msgs::Pose pose;
00101 pose.position.x = pose.position.y = pose.position.z = 0.0;
00102 pose.orientation = identityQuaternion();
00103 return pose;
00104 }
00105 static geometry_msgs::Quaternion identityQuaternion()
00106 {
00107 geometry_msgs::Quaternion q;
00108 q.x = q.y = q.z = 0.0;
00109 q.w = 1.0;
00110 return q;
00111 }
00112
00113 GraspInfo()
00114 {
00115 reset();
00116 }
00117 void reset()
00118 {
00119 object_manipulation_msgs::GraspableObject foo;
00120 object_ = foo;
00121 grasp_.grasp_pose = verticalGripper();
00122 object_.reference_frame_id = "base_link";
00123 object_orientation_ = identityQuaternion();
00124 }
00125 std::string object_collision_name_;
00126 object_manipulation_msgs::GraspableObject object_;
00127 object_manipulation_msgs::Grasp grasp_;
00128 geometry_msgs::Quaternion object_orientation_;
00129 };
00130
00131 GraspInfo* getGraspInfo(std::string arm_name)
00132 {
00133 if (arm_name=="right_arm") return &grasp_info_right_;
00134 return &grasp_info_left_;
00135 }
00136
00137
00138 void actionCallback(const pr2_object_manipulation_msgs::IMGUIGoalConstPtr &goal);
00139 void imageClickCallback(const pr2_object_manipulation_msgs::ImageClickConstPtr &click);
00140 void pickupFeedbackCallback(const object_manipulation_msgs::PickupFeedbackConstPtr &feedback);
00141 bool interruptRequested();
00142 bool checkInterrupts();
00143 void setStatusLabel(std::string text);
00144
00145
00146 int pickupObject(const pr2_object_manipulation_msgs::IMGUIOptions &options,
00147 object_manipulation_msgs::GraspableObject object = object_manipulation_msgs::GraspableObject() );
00148 int placeObject(const pr2_object_manipulation_msgs::IMGUIOptions &options);
00149 int plannedMove(const pr2_object_manipulation_msgs::IMGUIOptions &options);
00150 void collisionReset(int reset_choice, int arm_selection_choice);
00151 void lookAtTable();
00152 void armMotion(int arm_selection_choice, int arm_action_choice,
00153 int arm_planner_choice, bool collision, object_manipulation_msgs::ManipulationResult &result);
00154 void openCloseGripper(pr2_object_manipulation_msgs::IMGUIOptions options);
00155 int modelObject(pr2_object_manipulation_msgs::IMGUIOptions options);
00156 int runScriptedAction(std::string action_name, std::string group_name, pr2_object_manipulation_msgs::IMGUIOptions options);
00157
00158
00159 bool processCollisionMapForPickup(const pr2_object_manipulation_msgs::IMGUIOptions &options, object_manipulation_msgs::PickupGoal &goal);
00160 int callGhostedGripperPickup( std::string arm_name, object_manipulation_msgs::Grasp &grasp );
00161 int callGhostedGripperMove( std::string arm_name, geometry_msgs::PoseStamped &location );
00162 int callGhostedGripper(const pr2_object_manipulation_msgs::GetGripperPoseGoal &goal,
00163 pr2_object_manipulation_msgs::GetGripperPoseResult &result );
00164 bool getGrasp(object_manipulation_msgs::Grasp &grasp, std::string arm_name,
00165 geometry_msgs::PoseStamped grasp_pose, float gripper_opening);
00166
00167
00168 void testGripperPoseCallback(const pr2_object_manipulation_msgs::TestGripperPoseGoalConstPtr &goal);
00169 void testGripperPoseForGraspCallback(const pr2_object_manipulation_msgs::TestGripperPoseGoalConstPtr &goal);
00170 void testGripperPoseForPlaceCallback(const pr2_object_manipulation_msgs::TestGripperPoseGoalConstPtr &goal);
00171 void testGripperPoseForMoveCallback(const pr2_object_manipulation_msgs::TestGripperPoseGoalConstPtr &goal);
00172
00173
00174 ros::NodeHandle root_nh_;
00175 ros::NodeHandle priv_nh_;
00176
00177
00178 actionlib::SimpleActionServer<pr2_object_manipulation_msgs::IMGUIAction> *action_server_;
00179 actionlib::SimpleActionServer<pr2_object_manipulation_msgs::TestGripperPoseAction> *test_gripper_pose_server_;
00180
00181
00182 ros::Publisher status_pub_;
00183
00184
00185 object_manipulator::ActionWrapper<object_manipulation_msgs::PickupAction> pickup_client_;
00186 object_manipulator::ActionWrapper<object_manipulation_msgs::PlaceAction> place_client_;
00187 object_manipulator::ActionWrapper<pr2_create_object_model::ModelObjectInHandAction> create_model_client_;
00188 object_manipulator::ActionWrapper<pr2_object_manipulation_msgs::GetGripperPoseAction> get_gripper_pose_client_;
00189 object_manipulator::ActionWrapper<pr2_object_manipulation_msgs::RunScriptAction> run_script_client_;
00190 object_manipulator::ActionWrapper<move_base_msgs::MoveBaseAction> move_base_client_;
00191
00192
00193 object_manipulator::ServiceWrapper<std_srvs::Empty> collider_node_reset_srv_;
00194
00195
00196 ros::Subscriber image_click_sub_;
00197
00198
00199 enum Action {PICKUP, PLACE, MOVE};
00200 Action current_action_;
00201 object_manipulation_msgs::PickupGoal current_pickup_goal_;
00202 object_manipulation_msgs::PlaceGoal current_place_goal_;
00203 boost::mutex pipeline_mutex_;
00204 pr2_object_manipulation_msgs::IMGUIOptions options_;
00205
00206
00207 GripperController gripper_controller_;
00208 tabletop_collision_map_processing::CollisionMapInterface collision_map_interface_;
00209 object_manipulator::MechanismInterface mech_interface_;
00210
00211 std::string action_name_;
00212 std::string test_gripper_pose_action_name_;
00213 std::string interactive_manipulation_status_name_;
00214 std::string image_click_name_;
00215
00216
00217 GraspInfo grasp_info_right_;
00218 GraspInfo grasp_info_left_;
00219 sensor_msgs::PointCloud2 object_model_left_;
00220 sensor_msgs::PointCloud2 object_model_right_;
00221
00222 tf::TransformListener listener_;
00223
00224
00225 double cartesian_dist_tol_;
00226 double cartesian_angle_tol_;
00227 double cartesian_overshoot_dist_;
00228 double cartesian_overshoot_angle_;
00229
00230 };
00231
00232 }
00233
00234 #endif