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