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