$search
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 #include "pr2_interactive_manipulation/interactive_manipulation_backend.h" 00031 00032 #include <std_msgs/String.h> 00033 00034 #include <tf/transform_datatypes.h> 00035 #include <tf/transform_listener.h> 00036 #include <object_manipulation_msgs/Grasp.h> 00037 #include <object_manipulation_msgs/ClusterBoundingBox.h> 00038 #include <object_manipulation_msgs/tools.h> 00039 00040 #include <object_manipulator/tools/vector_tools.h> 00041 #include <object_manipulator/tools/arm_configurations.h> 00042 #include <sensor_msgs/point_cloud_conversion.h> 00043 00044 using object_manipulation_msgs::ManipulationResult; 00045 using object_manipulator::InterruptRequestedException; 00046 using pr2_object_manipulation_msgs::TestGripperPoseAction; 00047 using pr2_object_manipulation_msgs::TestGripperPoseGoal; 00048 using pr2_object_manipulation_msgs::TestGripperPoseGoalConstPtr; 00049 using pr2_object_manipulation_msgs::GetGripperPoseAction; 00050 using pr2_object_manipulation_msgs::GetGripperPoseGoal; 00051 using pr2_object_manipulation_msgs::GetGripperPoseResult; 00052 //using namespace pr2_object_manipulation_msgs; // For IMGUI stuff 00053 00054 namespace pr2_interactive_manipulation { 00055 00056 typedef actionlib::SimpleActionClient<object_manipulation_msgs::PickupAction> PickupClient; 00057 00058 geometry_msgs::Pose translatePose(geometry_msgs::Pose pose_in, btVector3 translation) 00059 { 00060 tf::Transform trans_in; 00061 tf::poseMsgToTF(pose_in, trans_in); 00062 tf::StampedTransform translate_trans; 00063 translate_trans.setIdentity(); 00064 translate_trans.setOrigin(translation); 00065 tf::Transform trans_out = trans_in * translate_trans; 00066 geometry_msgs::Pose pose_out; 00067 tf::poseTFToMsg(trans_out, pose_out); 00068 return pose_out; 00069 } 00070 00071 geometry_msgs::Pose preTranslatePose(geometry_msgs::Pose pose_in, btVector3 translation) 00072 { 00073 tf::Transform trans_in; 00074 tf::poseMsgToTF(pose_in, trans_in); 00075 tf::StampedTransform translate_trans; 00076 translate_trans.setIdentity(); 00077 translate_trans.setOrigin(translation); 00078 tf::Transform trans_out = translate_trans * trans_in; 00079 geometry_msgs::Pose pose_out; 00080 tf::poseTFToMsg(trans_out, pose_out); 00081 return pose_out; 00082 } 00083 00084 InteractiveManipulationBackend::InteractiveManipulationBackend() : 00085 root_nh_(""), 00086 priv_nh_("~"), 00087 pickup_client_("/object_manipulator/object_manipulator_pickup", true), 00088 place_client_("/object_manipulator/object_manipulator_place", true), 00089 create_model_client_("/create_object_model_server/model_object_in_hand_action", true), 00090 get_gripper_pose_client_("/get_pose_server", true), 00091 run_script_client_("run_rcommander_action", true), 00092 move_base_client_("move_base", true), 00093 collider_node_reset_srv_("/collider_node/reset") 00094 { 00095 priv_nh_.param<double>("cartesian_dist_tol", cartesian_dist_tol_, .01); 00096 priv_nh_.param<double>("cartesian_angle_tol", cartesian_angle_tol_, .087); 00097 priv_nh_.param<double>("cartesian_overshoot_dist", cartesian_overshoot_dist_, .005); 00098 priv_nh_.param<double>("cartesian_overshoot_angle", cartesian_overshoot_angle_, .087); 00099 00100 action_name_ = "imgui_action"; 00101 action_server_ = new actionlib::SimpleActionServer<pr2_object_manipulation_msgs::IMGUIAction>(root_nh_, action_name_, 00102 boost::bind(&InteractiveManipulationBackend::actionCallback, this, _1), 00103 false); 00104 action_server_->start(); 00105 00106 test_gripper_pose_action_name_="test_gripper_pose"; 00107 test_gripper_pose_server_ = new actionlib::SimpleActionServer<TestGripperPoseAction>(root_nh_, 00108 test_gripper_pose_action_name_, 00109 boost::bind(&InteractiveManipulationBackend::testGripperPoseCallback, this, _1), 00110 false); 00111 test_gripper_pose_server_->start(); 00112 00113 interactive_manipulation_status_name_ = "interactive_manipulation_status"; 00114 status_pub_ = root_nh_.advertise<std_msgs::String>(interactive_manipulation_status_name_, 1, true ); 00115 00116 image_click_name_ = "/interactive_manipulation_image_click"; 00117 image_click_sub_ = root_nh_.subscribe(image_click_name_, 1, &InteractiveManipulationBackend::imageClickCallback, this); 00118 00119 pickup_client_.setInterruptFunction(boost::bind(&InteractiveManipulationBackend::interruptRequested, this)); 00120 place_client_.setInterruptFunction(boost::bind(&InteractiveManipulationBackend::interruptRequested, this)); 00121 create_model_client_.setInterruptFunction(boost::bind(&InteractiveManipulationBackend::interruptRequested, this)); 00122 get_gripper_pose_client_.setInterruptFunction(boost::bind(&InteractiveManipulationBackend::interruptRequested, this)); 00123 00124 ROS_INFO("IM Backend ready"); 00125 } 00126 00127 InteractiveManipulationBackend::~InteractiveManipulationBackend() 00128 { 00129 delete action_server_; 00130 delete test_gripper_pose_server_; 00131 } 00132 00133 void InteractiveManipulationBackend::actionCallback(const pr2_object_manipulation_msgs::IMGUIGoalConstPtr &goal) 00134 { 00135 //boost::mutex::scoped_try_lock stl(action_mutex_) 00136 ROS_DEBUG("IM Backend received goal with command %d", goal->command.command); 00137 pr2_object_manipulation_msgs::IMGUIResult im_result; 00138 try 00139 { 00140 switch (goal->command.command) 00141 { 00142 case pr2_object_manipulation_msgs::IMGUICommand::PICKUP: 00143 if (goal->options.grasp_selection == 0) im_result.result.value = pickupObject(goal->options); 00144 else im_result.result.value = pickupObject(goal->options, goal->options.selected_object); 00145 break; 00146 case pr2_object_manipulation_msgs::IMGUICommand::PLACE: 00147 im_result.result.value = placeObject(goal->options); 00148 break; 00149 case pr2_object_manipulation_msgs::IMGUICommand::PLANNED_MOVE: 00150 im_result.result.value = plannedMove(goal->options); 00151 break; 00152 case pr2_object_manipulation_msgs::IMGUICommand::RESET: 00153 collisionReset(goal->options.reset_choice, goal->options.arm_selection); 00154 im_result.result.value = object_manipulation_msgs::ManipulationResult::SUCCESS; 00155 break; 00156 case pr2_object_manipulation_msgs::IMGUICommand::MOVE_ARM: 00157 armMotion(goal->options.arm_selection, goal->options.arm_action_choice, 00158 goal->options.arm_planner_choice, goal->options.collision_checked, im_result.result); 00159 break; 00160 case pr2_object_manipulation_msgs::IMGUICommand::MOVE_GRIPPER: 00161 openCloseGripper(goal->options); 00162 im_result.result.value = object_manipulation_msgs::ManipulationResult::SUCCESS; 00163 break; 00164 case pr2_object_manipulation_msgs::IMGUICommand::LOOK_AT_TABLE: 00165 lookAtTable(); 00166 im_result.result.value = object_manipulation_msgs::ManipulationResult::SUCCESS; 00167 break; 00168 case pr2_object_manipulation_msgs::IMGUICommand::MODEL_OBJECT: 00169 im_result.result.value = modelObject(goal->options); 00170 break; 00171 case pr2_object_manipulation_msgs::IMGUICommand::SCRIPTED_ACTION: 00172 im_result.result.value = runScriptedAction(goal->command.script_name, 00173 goal->command.script_group_name, 00174 goal->options); 00175 break; 00176 case pr2_object_manipulation_msgs::IMGUICommand::STOP_NAV: 00177 move_base_client_.client().cancelAllGoals(); 00178 break; 00179 default: 00180 ROS_ERROR("IM Backend could not understand command: %d", goal->command.command); 00181 setStatusLabel("Command not yet implemented"); 00182 im_result.result.value = object_manipulation_msgs::ManipulationResult::ERROR; 00183 } 00184 action_server_->setSucceeded(im_result); 00185 ROS_DEBUG("IM Backend: goal finished"); 00186 } 00187 catch (InterruptRequestedException &ex) 00188 { 00189 if (pickup_client_.isInitialized()) pickup_client_.client().cancelAllGoals(); 00190 if (place_client_.isInitialized()) place_client_.client().cancelAllGoals(); 00191 if (create_model_client_.isInitialized()) create_model_client_.client().cancelAllGoals(); 00192 if (get_gripper_pose_client_.isInitialized()) get_gripper_pose_client_.client().cancelAllGoals(); 00193 if (run_script_client_.isInitialized()) run_script_client_.client().cancelAllGoals(); 00194 im_result.result.value = object_manipulation_msgs::ManipulationResult::CANCELLED; 00195 action_server_->setSucceeded(im_result); 00196 ROS_INFO("IM Backend: cancelled"); 00197 setStatusLabel("cancelled."); 00198 } 00199 catch (object_manipulator::ServiceNotFoundException &ex) 00200 { 00201 setStatusLabel("a needed service or action server was not found"); 00202 im_result.result.value = im_result.result.ERROR; 00203 action_server_->setSucceeded(im_result); 00204 } 00205 } 00206 00207 bool InteractiveManipulationBackend::getGrasp(object_manipulation_msgs::Grasp &grasp, std::string arm_name, 00208 geometry_msgs::PoseStamped grasp_pose, float gripper_opening) 00209 { 00210 std::vector<std::string> joint_names = object_manipulator::handDescription().handJointNames(arm_name); 00211 grasp.pre_grasp_posture.name = joint_names; 00212 grasp.grasp_posture.name = joint_names; 00213 grasp.pre_grasp_posture.position.resize( joint_names.size(), gripper_opening); 00214 grasp.grasp_posture.position.resize( joint_names.size(), 0.0); 00215 grasp.grasp_posture.effort.resize(joint_names.size(), 50); 00216 grasp.pre_grasp_posture.effort.resize(joint_names.size(), 100); 00217 grasp.desired_approach_distance = options_.adv_options.desired_approach / 100.; 00218 grasp.min_approach_distance = options_.adv_options.min_approach / 100.; 00219 geometry_msgs::PoseStamped pose_stamped_in = grasp_pose; 00220 pose_stamped_in.header.stamp = ros::Time(0); 00221 geometry_msgs::PoseStamped pose_stamped; 00222 try 00223 { 00224 listener_.transformPose("base_link", pose_stamped_in, pose_stamped); 00225 } 00226 catch (tf::TransformException ex) 00227 { 00228 ROS_ERROR("Failed to transform gripper click grasp to %s frame; exception: %s", 00229 grasp_pose.header.frame_id.c_str(), ex.what()); 00230 setStatusLabel("Failed to transform gripper click grasp"); 00231 return false; 00232 } 00233 grasp.grasp_pose = pose_stamped.pose; 00234 grasp.success_probability = 1.0; 00235 return true; 00236 } 00237 00238 void InteractiveManipulationBackend::setStatusLabel(std::string text) 00239 { 00240 if (action_server_->isActive()) 00241 { 00242 pr2_object_manipulation_msgs::IMGUIFeedback feedback; 00243 feedback.status = text; 00244 action_server_->publishFeedback(feedback); 00245 } 00246 std_msgs::String msg; 00247 msg.data = text; 00248 status_pub_.publish(msg); 00249 ROS_INFO_STREAM("IM backend feedback: " << text); 00250 } 00251 00252 bool InteractiveManipulationBackend::interruptRequested() 00253 { 00254 return ( !priv_nh_.ok() || action_server_->isPreemptRequested() ); 00255 } 00256 00257 bool InteractiveManipulationBackend::checkInterrupts() 00258 { 00259 if ( interruptRequested() ) throw object_manipulator::InterruptRequestedException(); 00260 return true; 00261 } 00262 00263 void populateGraspOptions(const pr2_object_manipulation_msgs::IMGUIOptions &options, 00264 object_manipulation_msgs::PickupGoal &pickup_goal) 00265 { 00266 if (options.arm_selection == 0) pickup_goal.arm_name = "right_arm"; 00267 else pickup_goal.arm_name = "left_arm"; 00268 if ( options.adv_options.lift_direction_choice != 0) 00269 { 00270 if (pickup_goal.arm_name == "right_arm") pickup_goal.lift.direction.header.frame_id = "r_wrist_roll_link"; 00271 else pickup_goal.lift.direction.header.frame_id = "l_wrist_roll_link"; 00272 pickup_goal.lift.direction.vector.x = -1; 00273 pickup_goal.lift.direction.vector.y = 0; 00274 pickup_goal.lift.direction.vector.z = 0; 00275 } 00276 else 00277 { 00278 pickup_goal.lift.direction.header.frame_id = "base_link"; 00279 pickup_goal.lift.direction.vector.x = 0; 00280 pickup_goal.lift.direction.vector.y = 0; 00281 pickup_goal.lift.direction.vector.z = 1; 00282 } 00283 pickup_goal.lift.desired_distance = options.adv_options.lift_steps * 0.01; 00284 pickup_goal.lift.min_distance = pickup_goal.lift.desired_distance / 2.0; 00285 pickup_goal.use_reactive_lift = options.adv_options.reactive_force; 00286 pickup_goal.use_reactive_execution = options.adv_options.reactive_grasping; 00287 pickup_goal.movable_obstacles = options.movable_obstacles; 00288 pickup_goal.max_contact_force = options.adv_options.max_contact_force; 00289 00290 //using unsafe_grasp_execution 00291 if (!options.collision_checked) 00292 { 00293 ROS_WARN("setting ignore_collisions to true"); 00294 pickup_goal.ignore_collisions = true; 00295 } 00296 } 00297 00298 bool InteractiveManipulationBackend::processCollisionMapForPickup(const pr2_object_manipulation_msgs::IMGUIOptions &options, 00299 object_manipulation_msgs::PickupGoal &goal) 00300 { 00301 if (options.collision_checked) 00302 { 00303 // make sure collision services are available 00304 setStatusLabel("waiting for collision map services..."); 00305 ros::Time start_time = ros::Time::now(); 00306 while (!collision_map_interface_.connectionsEstablished(ros::Duration(1.0)) && checkInterrupts()) 00307 { 00308 if (ros::Time::now() - start_time >= ros::Duration(5.0)) 00309 { 00310 setStatusLabel("collision map services not found"); 00311 return false; 00312 } 00313 } 00314 if (!goal.target.potential_models.empty()) 00315 { 00316 //if we have a potential recognized model, we will use its mesh 00317 try 00318 { 00319 //collision_map_interface_.processCollisionGeometryForObjectAsBoundingBox(goal.target.potential_models[0], 00320 // goal.collision_object_name); 00321 ROS_WARN("Adding full target object mesh to collision map - needed for push-grasping, but slow otherwise..."); 00322 collision_map_interface_.processCollisionGeometryForObject(goal.target.potential_models[0], 00323 goal.collision_object_name); 00324 } 00325 catch (tabletop_collision_map_processing::CollisionMapException &ex) 00326 { 00327 setStatusLabel("failed to add mesh to collision map"); 00328 return false; 00329 } 00330 } 00331 else if ( !goal.target.cluster.points.empty() ) 00332 { 00333 //if we have a point cloud, we will use its bounding box as the collision object 00334 object_manipulation_msgs::ClusterBoundingBox bbox; 00335 try 00336 { 00337 collision_map_interface_.getClusterBoundingBox(goal.target.cluster, bbox.pose_stamped, bbox.dimensions); 00338 collision_map_interface_.processCollisionGeometryForBoundingBox(bbox, goal.collision_object_name); 00339 } 00340 catch (tabletop_collision_map_processing::CollisionMapException &ex) 00341 { 00342 ROS_ERROR_STREAM("Exception: " << ex.what()); 00343 setStatusLabel("failed to compute object bounding box"); 00344 return false; 00345 } 00346 } 00347 else 00348 { 00349 //if not, then the gripper can hit anything during approach and lift 00350 goal.collision_support_surface_name = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00351 goal.allow_gripper_support_collision = true; 00352 } 00353 //also set small padding on fingertip links 00354 goal.additional_link_padding = object_manipulator::concat( 00355 object_manipulator::MechanismInterface::gripperPadding("left_arm", 0.00), 00356 object_manipulator::MechanismInterface::gripperPadding("right_arm", 0.00) ); 00357 } 00358 else 00359 { 00360 //if collisions are disabled, anything can hit anything 00361 arm_navigation_msgs::CollisionOperation coll; 00362 coll.object1 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00363 coll.object2 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00364 coll.operation = arm_navigation_msgs::CollisionOperation::DISABLE; 00365 goal.additional_collision_operations.collision_operations.push_back(coll); 00366 } 00367 return true; 00368 } 00369 00370 void InteractiveManipulationBackend::testGripperPoseCallback(const TestGripperPoseGoalConstPtr &goal) 00371 { 00372 switch (current_action_) 00373 { 00374 case PICKUP: testGripperPoseForGraspCallback(goal); break; 00375 case PLACE: testGripperPoseForPlaceCallback(goal); break; 00376 case MOVE: testGripperPoseForMoveCallback(goal); break; 00377 default: ROS_ERROR("Unknown current action in testGripperPoseCallback"); 00378 } 00379 } 00380 00381 void InteractiveManipulationBackend::testGripperPoseForGraspCallback(const TestGripperPoseGoalConstPtr &goal) 00382 { 00383 boost::mutex::scoped_lock lock(pipeline_mutex_); 00384 ROS_INFO("Request for grasp feedback received"); 00385 pr2_object_manipulation_msgs::TestGripperPoseResult result; 00386 result.valid.resize(goal->gripper_poses.size(), false); 00387 00388 if (goal->gripper_poses.size() != goal->gripper_openings.size()) 00389 { 00390 ROS_ERROR("Size mismatch in TestGripperPose goal"); 00391 test_gripper_pose_server_->setSucceeded(result); 00392 } 00393 00394 current_pickup_goal_.desired_grasps.clear(); 00395 current_pickup_goal_.only_perform_feasibility_test = true; 00396 for (size_t i=0; i<goal->gripper_poses.size(); i++) 00397 { 00398 object_manipulation_msgs::Grasp grasp; 00399 if (!getGrasp(grasp, current_pickup_goal_.arm_name, goal->gripper_poses[i], goal->gripper_openings[i])) 00400 { 00401 setStatusLabel("Grasp test error (conversion to grasp failed)"); 00402 test_gripper_pose_server_->setSucceeded(result); 00403 return; 00404 } 00405 current_pickup_goal_.desired_grasps.push_back(grasp); 00406 } 00407 00408 setStatusLabel("Testing grasps..."); 00409 pickup_client_.client().sendGoal(current_pickup_goal_); 00410 while (!pickup_client_.client().waitForResult(ros::Duration(1.0)) && !test_gripper_pose_server_->isPreemptRequested()) 00411 { 00412 ROS_DEBUG("Waiting for pickup result.."); 00413 } 00414 if (test_gripper_pose_server_->isPreemptRequested()) 00415 { 00416 setStatusLabel("Grasp test canceled"); 00417 pickup_client_.client().cancelGoal(); 00418 test_gripper_pose_server_->setAborted(result); 00419 return; 00420 } 00421 00422 object_manipulation_msgs::PickupResult pickup_result = *(pickup_client_.client().getResult()); 00423 if (pickup_result.attempted_grasp_results.size() > result.valid.size()) 00424 { 00425 ROS_ERROR("Size mismatch in list of tested grasps"); 00426 test_gripper_pose_server_->setSucceeded(result); 00427 } 00428 bool one_good = false; 00429 for (size_t i=0; i<pickup_result.attempted_grasp_results.size(); i++) 00430 { 00431 if (pickup_result.attempted_grasp_results[i].result_code == object_manipulation_msgs::GraspResult::SUCCESS) 00432 { 00433 result.valid[i] = true; 00434 one_good = true; 00435 } 00436 } 00437 if (goal->gripper_poses.size() == 1) 00438 { 00439 if (pickup_result.attempted_grasp_results.empty()) ROS_ERROR("Empty list of attempted grasps in test"); 00440 else if (result.valid[0]) setStatusLabel("grasp is good"); 00441 else setStatusLabel(object_manipulation_msgs::getGraspResultInfo(pickup_result.attempted_grasp_results[0])); 00442 } 00443 else if (one_good) setStatusLabel("at least one good grasp found"); 00444 else setStatusLabel("all grasps failed"); 00445 00446 test_gripper_pose_server_->setSucceeded(result); 00447 } 00448 00449 void InteractiveManipulationBackend::testGripperPoseForPlaceCallback(const TestGripperPoseGoalConstPtr &goal) 00450 { 00451 boost::mutex::scoped_lock lock(pipeline_mutex_); 00452 ROS_INFO("Request for place feedback received"); 00453 pr2_object_manipulation_msgs::TestGripperPoseResult result; 00454 result.valid.resize(goal->gripper_poses.size(), false); 00455 00456 current_place_goal_.place_locations.clear(); 00457 current_place_goal_.only_perform_feasibility_test = true; 00458 for (size_t i=0; i<goal->gripper_poses.size(); i++) 00459 { 00460 current_place_goal_.place_locations.push_back(goal->gripper_poses[i]); 00461 } 00462 00463 setStatusLabel("Testing places..."); 00464 place_client_.client().sendGoal(current_place_goal_); 00465 while (!place_client_.client().waitForResult(ros::Duration(1.0)) && !test_gripper_pose_server_->isPreemptRequested()) 00466 { 00467 ROS_DEBUG("Waiting for place results.."); 00468 } 00469 if (test_gripper_pose_server_->isPreemptRequested()) 00470 { 00471 setStatusLabel("Place test canceled"); 00472 place_client_.client().cancelGoal(); 00473 test_gripper_pose_server_->setAborted(result); 00474 return; 00475 } 00476 00477 object_manipulation_msgs::PlaceResult place_result = *(place_client_.client().getResult()); 00478 if (place_result.attempted_location_results.size() > result.valid.size()) 00479 { 00480 ROS_ERROR("Size mismatch in list of tested places"); 00481 test_gripper_pose_server_->setSucceeded(result); 00482 } 00483 bool one_good = false; 00484 for (size_t i=0; i<place_result.attempted_location_results.size(); i++) 00485 { 00486 if (place_result.attempted_location_results[i].result_code == object_manipulation_msgs::PlaceLocationResult::SUCCESS) 00487 { 00488 result.valid[i] = true; 00489 one_good = true; 00490 } 00491 } 00492 if (goal->gripper_poses.size() == 1) 00493 { 00494 if (place_result.attempted_location_results.empty()) ROS_ERROR("Empty list of attempted locations in test"); 00495 else if (result.valid[0]) setStatusLabel("place is good"); 00496 else setStatusLabel(object_manipulation_msgs::getPlaceLocationResultInfo( 00497 place_result.attempted_location_results[0])); 00498 } 00499 else if (one_good) setStatusLabel("at least one good place found"); 00500 else setStatusLabel("all places failed"); 00501 test_gripper_pose_server_->setSucceeded(result); 00502 } 00503 00504 00505 void InteractiveManipulationBackend::testGripperPoseForMoveCallback(const TestGripperPoseGoalConstPtr &goal) 00506 { 00507 ROS_INFO("Request for move feedback received"); 00508 pr2_object_manipulation_msgs::TestGripperPoseResult result; 00509 result.valid.resize(goal->gripper_poses.size(), false); 00510 00511 std::string arm_name; 00512 if (options_.arm_selection == 0) arm_name = "right_arm"; 00513 else arm_name = "left_arm"; 00514 00515 arm_navigation_msgs::OrderedCollisionOperations collision_operations; 00516 if (!options_.collision_checked) 00517 { 00518 //if collisions off, disable anything against anything 00519 arm_navigation_msgs::CollisionOperation coll; 00520 coll.object1 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00521 coll.object2 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00522 coll.operation = arm_navigation_msgs::CollisionOperation::DISABLE; 00523 collision_operations.collision_operations.push_back(coll); 00524 } 00525 00526 //check that the desired pose has a collision-free IK solution 00527 std::vector<arm_navigation_msgs::LinkPadding> link_padding; 00528 kinematics_msgs::GetConstraintAwarePositionIK::Response ik_response; 00529 mech_interface_.getPlanningScene(collision_operations, link_padding); 00530 bool one_good = false; 00531 for (size_t i=0; i<goal->gripper_poses.size(); i++) 00532 { 00533 geometry_msgs::PoseStamped test_pose = goal->gripper_poses[i]; 00534 test_pose.header.stamp = ros::Time::now(); 00535 //clean up leading slash, for now 00536 if (!test_pose.header.frame_id.empty() && test_pose.header.frame_id.at(0)=='/') 00537 { 00538 test_pose.header.frame_id = test_pose.header.frame_id.substr(1, test_pose.header.frame_id.size()-1); 00539 } 00540 if(mech_interface_.getIKForPose(arm_name, test_pose, ik_response, collision_operations, link_padding)) 00541 { 00542 result.valid[i] = true; 00543 one_good = true; 00544 } 00545 } 00546 if (goal->gripper_poses.size()==1) 00547 { 00548 if (result.valid[0]) setStatusLabel("Gripper pose is good"); 00549 else if (options_.collision_checked) setStatusLabel("Gripper pose is out of reach or in collision"); 00550 else setStatusLabel("Gripper pose is out of reach"); 00551 } 00552 else 00553 { 00554 if (one_good) setStatusLabel("At least one gripper pose is good"); 00555 else if (options_.collision_checked) setStatusLabel("All gripper poses are out of reach or in collision"); 00556 else setStatusLabel("All gripper pose are out of reach"); 00557 } 00558 test_gripper_pose_server_->setSucceeded(result); 00559 } 00560 00561 00562 int InteractiveManipulationBackend::plannedMove(const pr2_object_manipulation_msgs::IMGUIOptions &options) 00563 { 00564 options_ = options; 00565 current_action_ = MOVE; 00566 00567 std::string arm_name; 00568 if (options.arm_selection == 0) arm_name = "right_arm"; 00569 else arm_name = "left_arm"; 00570 00571 //call ghosted gripper to get move-to location 00572 geometry_msgs::PoseStamped location; 00573 00574 ROS_INFO("plannedMove called on %s", arm_name.c_str()); 00575 int planning_result = callGhostedGripperMove(arm_name, location); 00576 if ( planning_result != object_manipulation_msgs::ManipulationResult::SUCCESS ) return planning_result; 00577 00578 //clean up leading slash, for now 00579 if (!location.header.frame_id.empty() && location.header.frame_id.at(0)=='/') 00580 { 00581 location.header.frame_id = location.header.frame_id.substr(1, location.header.frame_id.size()-1); 00582 } 00583 //ask move_arm to get us there 00584 arm_navigation_msgs::OrderedCollisionOperations collision_operations; 00585 bool success; 00586 if (!options_.collision_checked) 00587 { 00588 //use Cartesian controllers to just move us straight there, if we're ignoring collisions 00589 success = mech_interface_.moveArmToPoseCartesian(arm_name, location, ros::Duration(15.0)); 00590 /* 00591 //if collisions off, disable anything against anything 00592 arm_navigation_msgs::CollisionOperation coll; 00593 coll.object1 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00594 coll.object2 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00595 coll.operation = arm_navigation_msgs::CollisionOperation::DISABLE; 00596 collision_operations.collision_operations.push_back(coll); 00597 */ 00598 } 00599 else 00600 { 00601 std::vector<arm_navigation_msgs::LinkPadding> link_padding; 00602 success = mech_interface_.moveArmToPose(arm_name, location, collision_operations, link_padding); 00603 } 00604 if(success){ 00605 setStatusLabel("planned move completed"); 00606 return object_manipulation_msgs::ManipulationResult::SUCCESS; 00607 } 00608 setStatusLabel("planned move failed"); 00609 return object_manipulation_msgs::ManipulationResult::FAILED; 00610 } 00611 00612 00613 int InteractiveManipulationBackend::pickupObject(const pr2_object_manipulation_msgs::IMGUIOptions &options, 00614 object_manipulation_msgs::GraspableObject object) 00615 { 00616 options_ = options; 00617 ROS_INFO("Graspable object has %d points and %d database models", 00618 (int)object.cluster.points.size(), (int)object.potential_models.size()); 00619 //convert the graspable object to base link frame. this also sets its reference_frame_id to that 00620 //so any grasps returned will be in that frame 00621 try 00622 { 00623 mech_interface_.convertGraspableObjectComponentsToFrame(object, "base_link"); 00624 } 00625 catch(object_manipulator::MechanismException &ex) 00626 { 00627 ROS_ERROR_STREAM("Conversion error: " << ex.what()); 00628 setStatusLabel("failed to convert object to desired frame"); 00629 return object_manipulation_msgs::ManipulationResult::ERROR; 00630 } 00631 00632 //prepare pickup goal 00633 object_manipulation_msgs::PickupGoal pickup_goal; 00634 pickup_goal.target = object; 00635 if (!processCollisionMapForPickup(options, pickup_goal)) return object_manipulation_msgs::ManipulationResult::ERROR; 00636 populateGraspOptions(options, pickup_goal); 00637 00638 //from this point on, if we get a cancellation we must clear the collision object 00639 try 00640 { 00641 //save this as the current pickup goal 00642 pipeline_mutex_.lock(); 00643 current_pickup_goal_ = pickup_goal; 00644 current_action_ = PICKUP; 00645 pipeline_mutex_.unlock(); 00646 00647 //if the object is empty, ask the user for help on desired grasps 00648 if ( object.cluster.points.empty() && object.potential_models.empty() ) 00649 { 00650 object_manipulation_msgs::Grasp grasp; 00651 int success = callGhostedGripperPickup( pickup_goal.arm_name, grasp ); 00652 if ( success != object_manipulation_msgs::ManipulationResult::SUCCESS ) return success; 00653 grasp.desired_approach_distance = options_.adv_options.desired_approach / 100.; 00654 grasp.min_approach_distance = options_.adv_options.min_approach / 100.; 00655 pickup_goal.desired_grasps.push_back(grasp); 00656 } 00657 00658 //call pickup and wait for operation to finish 00659 pickup_goal.only_perform_feasibility_test = false; 00660 setStatusLabel("calling pickup action..."); 00661 //at this point, we can lock the pipeline for good 00662 boost::mutex::scoped_lock lock(pipeline_mutex_); 00663 pickup_client_.client().sendGoal(pickup_goal, PickupClient::SimpleDoneCallback(), 00664 PickupClient::SimpleActiveCallback(), 00665 boost::bind(&InteractiveManipulationBackend::pickupFeedbackCallback, this, _1)); 00666 pickup_client_.waitForResult(); 00667 00668 //get back pickup result 00669 object_manipulation_msgs::PickupResult pickup_result = *(pickup_client_.client().getResult()); 00670 00671 bool pickup_succeeded = true; 00672 if (pickup_client_.client().getState() != actionlib::SimpleClientGoalState::SUCCEEDED) pickup_succeeded = false; 00673 00674 if(!pickup_succeeded) 00675 { 00676 //if we failed with any result except LIFT_FAILED, in which case we are holding the object, 00677 //we want to get rid of if from the collision map 00678 if (pickup_result.manipulation_result.value != pickup_result.manipulation_result.LIFT_FAILED && 00679 !pickup_goal.collision_object_name.empty()) 00680 { 00681 collision_map_interface_.removeCollisionModel(pickup_goal.collision_object_name); 00682 } 00683 if (pickup_result.attempted_grasp_results.empty()) 00684 { 00685 setStatusLabel("pickup failed."); 00686 return object_manipulation_msgs::ManipulationResult::ERROR; 00687 } 00688 else 00689 { 00690 setStatusLabel("could not execute desired grasp"); 00691 //setStatusLabel(object_manipulation_msgs::getGraspResultInfo(pickup_result.attempted_grasp_results[0])); 00692 00693 //reset all attached objects for that arm, in case one was attached before the error 00694 mech_interface_.detachAllObjectsFromGripper(pickup_goal.arm_name); 00695 } 00696 return object_manipulation_msgs::ManipulationResult::UNFEASIBLE; 00697 } 00698 00699 //save object and grasp info for later 00700 getGraspInfo(pickup_goal.arm_name)->object_ = object; 00701 getGraspInfo(pickup_goal.arm_name)->object_collision_name_ = pickup_goal.collision_object_name; 00702 getGraspInfo(pickup_goal.arm_name)->grasp_ = pickup_result.grasp; 00703 getGraspInfo(pickup_goal.arm_name)->object_orientation_ = GraspInfo::identityQuaternion(); 00704 00705 setStatusLabel("grasp completed"); 00706 return object_manipulation_msgs::ManipulationResult::SUCCESS; 00707 } 00708 catch (InterruptRequestedException &ex) 00709 { 00710 if (!pickup_goal.collision_object_name.empty()) 00711 { 00712 collision_map_interface_.removeCollisionModel(pickup_goal.collision_object_name); 00713 } 00714 throw(ex); 00715 } 00716 } 00717 00718 void InteractiveManipulationBackend::pickupFeedbackCallback( 00719 const object_manipulation_msgs::PickupFeedbackConstPtr &feedback) 00720 { 00721 std::stringstream stat; 00722 stat << "trying grasp " << feedback->current_grasp+1 << "/" << feedback->total_grasps; 00723 setStatusLabel(stat.str()); 00724 } 00725 00726 void populatePlaceOptions(object_manipulation_msgs::PlaceGoal &place_goal, const pr2_object_manipulation_msgs::IMGUIOptions &options) 00727 { 00728 if (options.arm_selection == 0) place_goal.arm_name = "right_arm"; 00729 else place_goal.arm_name = "left_arm"; 00730 place_goal.place_padding = 0.0; 00731 place_goal.desired_retreat_distance = 0.1; 00732 place_goal.min_retreat_distance = 0.05; 00733 if (options.adv_options.lift_direction_choice == 0) 00734 { 00735 place_goal.approach.direction.header.frame_id = "base_link"; 00736 place_goal.approach.direction.vector.x = 0; 00737 place_goal.approach.direction.vector.y = 0; 00738 place_goal.approach.direction.vector.z = -1; 00739 } 00740 else 00741 { 00742 if (place_goal.arm_name == "right_arm") place_goal.approach.direction.header.frame_id = "r_wrist_roll_link"; 00743 else place_goal.approach.direction.header.frame_id = "l_wrist_roll_link"; 00744 place_goal.approach.direction.vector.x = 1; 00745 place_goal.approach.direction.vector.y = 0; 00746 place_goal.approach.direction.vector.z = 0; 00747 } 00748 place_goal.approach.desired_distance = options.adv_options.lift_steps * 0.01; 00749 place_goal.approach.min_distance = place_goal.approach.desired_distance * 0.5; 00750 place_goal.use_reactive_place = options.adv_options.reactive_place; 00751 } 00752 00753 int InteractiveManipulationBackend::placeObject(const pr2_object_manipulation_msgs::IMGUIOptions &options) 00754 { 00755 //prepare place goal 00756 object_manipulation_msgs::PlaceGoal place_goal; 00757 //note identity grasp; we will be going to the gripper pose specified by the user 00758 place_goal.grasp.grasp_pose.orientation.w = 1; 00759 populatePlaceOptions(place_goal, options); 00760 if (!options.collision_checked) 00761 { 00762 //collisions off, disable anything against anything 00763 arm_navigation_msgs::CollisionOperation coll; 00764 coll.object1 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00765 coll.object2 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00766 coll.operation = arm_navigation_msgs::CollisionOperation::DISABLE; 00767 place_goal.additional_collision_operations.collision_operations.push_back(coll); 00768 } 00769 else 00770 { 00771 //collisions on, 0 link padding on fingertips 00772 place_goal.additional_link_padding = 00773 object_manipulator::concat( object_manipulator::MechanismInterface::gripperPadding("left_arm", 0.0), 00774 object_manipulator::MechanismInterface::gripperPadding("right_arm", 0.0) ); 00775 //anything can be hit during move from pre-place to place 00776 place_goal.collision_support_surface_name = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00777 place_goal.allow_gripper_support_collision = true; 00778 //collision name of the currently grasped object 00779 place_goal.collision_object_name = getGraspInfo(place_goal.arm_name)->object_collision_name_; 00780 } 00781 00782 //save this as the current place goal 00783 pipeline_mutex_.lock(); 00784 current_place_goal_ = place_goal; 00785 current_action_ = PLACE; 00786 pipeline_mutex_.unlock(); 00787 00788 //call gripper click to get place location 00789 geometry_msgs::PoseStamped location; 00790 int planning_result = callGhostedGripperMove(place_goal.arm_name, location); 00791 if ( planning_result != object_manipulation_msgs::ManipulationResult::SUCCESS ) return planning_result; 00792 place_goal.place_locations.push_back(location); 00793 00794 //debug output 00795 geometry_msgs::Pose grasp_pose = place_goal.grasp.grasp_pose; 00796 ROS_INFO("Placing object %s on support %s using grasp: %f %f %f; %f %f %f %f", 00797 place_goal.collision_object_name.c_str(), place_goal.collision_support_surface_name.c_str(), 00798 grasp_pose.position.x, grasp_pose.position.y, grasp_pose.position.z, 00799 grasp_pose.orientation.x, grasp_pose.orientation.y, grasp_pose.orientation.z, grasp_pose.orientation.w); 00800 00801 //send the goal 00802 setStatusLabel("calling place action."); 00803 //at this point, we can lock the pipeline for good 00804 boost::mutex::scoped_lock lock(pipeline_mutex_); 00805 place_client_.client().sendGoal(place_goal); 00806 place_client_.waitForResult(); 00807 00808 //get the result 00809 object_manipulation_msgs::PlaceResult result = *(place_client_.client().getResult()); 00810 if (place_client_.client().getState() != actionlib::SimpleClientGoalState::SUCCEEDED) 00811 { 00812 if (result.attempted_location_results.empty()) 00813 { 00814 setStatusLabel("a serious error has occured, please call the WG helpdesk"); 00815 return object_manipulation_msgs::ManipulationResult::ERROR; 00816 } 00817 else 00818 { 00819 setStatusLabel(object_manipulation_msgs::getPlaceLocationResultInfo(result.attempted_location_results[0])); 00820 } 00821 return object_manipulation_msgs::ManipulationResult::UNFEASIBLE; 00822 } 00823 getGraspInfo(place_goal.arm_name)->reset(); 00824 setStatusLabel("place completed"); 00825 return object_manipulation_msgs::ManipulationResult::SUCCESS; 00826 } 00827 00828 void InteractiveManipulationBackend::collisionReset(int reset_choice, int arm_selection_choice) 00829 { 00830 try 00831 { 00832 std_srvs::Empty srv; 00833 switch (reset_choice) 00834 { 00835 case 0: 00836 //reset map and all collision objects 00837 collision_map_interface_.resetCollisionModels(); 00838 collision_map_interface_.resetAttachedModels(); 00839 getGraspInfo("right_arm")->reset(); 00840 getGraspInfo("left_arm")->reset(); 00841 if (!collider_node_reset_srv_.client().call(srv)) setStatusLabel("failed to call map reset client"); 00842 else setStatusLabel("collision map and all objects reset"); 00843 break; 00844 case 1: 00845 //reset all unattached collision objects 00846 collision_map_interface_.resetCollisionModels(); 00847 setStatusLabel("collision models reset"); 00848 break; 00849 case 2: 00850 //reset all attached objects 00851 collision_map_interface_.resetAttachedModels(); 00852 getGraspInfo("right_arm")->reset(); 00853 getGraspInfo("left_arm")->reset(); 00854 setStatusLabel("attached models reset"); 00855 break; 00856 case 3: 00857 //reset only attached objects for the selected arm 00858 if(arm_selection_choice == 0){ 00859 mech_interface_.detachAllObjectsFromGripper("right_arm"); 00860 getGraspInfo("right_arm")->reset(); 00861 setStatusLabel("reset models attached to right arm"); 00862 } 00863 else{ 00864 mech_interface_.detachAllObjectsFromGripper("left_arm"); 00865 getGraspInfo("left_arm")->reset(); 00866 setStatusLabel("reset models attached to left arm"); 00867 } 00868 break; 00869 case 4: 00870 { 00871 //reset collision map 00872 if (!collider_node_reset_srv_.client().call(srv)) setStatusLabel("failed to call reset client"); 00873 else setStatusLabel("collision map reset"); 00874 break; 00875 } 00876 default: 00877 setStatusLabel("could not understand collision reset request"); 00878 } 00879 } 00880 catch (tabletop_collision_map_processing::CollisionMapException &ex) 00881 { 00882 setStatusLabel("failed to perform requested collision operation"); 00883 } 00884 } 00885 00886 void InteractiveManipulationBackend::armMotion(int arm_selection_choice, int arm_action_choice, 00887 int arm_planner_choice, bool collision, 00888 ManipulationResult &result) 00889 { 00890 std::string arm_name; 00891 if ( arm_selection_choice == 0) arm_name = "right_arm"; 00892 else arm_name = "left_arm"; 00893 00894 try 00895 { 00896 ROS_DEBUG("Attempting arm motion"); 00897 arm_navigation_msgs::OrderedCollisionOperations ord; 00898 if (!collision) 00899 { 00900 arm_navigation_msgs::CollisionOperation coll; 00901 coll.object1 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00902 coll.object2 = arm_navigation_msgs::CollisionOperation::COLLISION_SET_ALL; 00903 coll.operation = arm_navigation_msgs::CollisionOperation::DISABLE; 00904 ord.collision_operations.push_back(coll); 00905 } 00906 std::vector<arm_navigation_msgs::LinkPadding> pad; 00907 if (collision) 00908 { 00909 pad = object_manipulator::concat( object_manipulator::MechanismInterface::gripperPadding("left_arm", 0.0), 00910 object_manipulator::MechanismInterface::gripperPadding("right_arm", 0.0) ); 00911 } 00912 00913 switch(arm_action_choice) 00914 { 00915 case 0: //side 00916 { 00917 if (arm_planner_choice == 0) 00918 { 00919 setStatusLabel("moving arm to side using motion planner"); 00920 if ( !mech_interface_.attemptMoveArmToGoal(arm_name, 00921 object_manipulator::armConfigurations().position(arm_name, "side"), ord, pad) ) 00922 { 00923 result.value = result.FAILED; 00924 setStatusLabel("failed to move arm to side (possible collisions)"); 00925 } 00926 else 00927 { 00928 setStatusLabel("arm moved to side"); 00929 result.value = result.SUCCESS; 00930 } 00931 } 00932 else 00933 { 00934 setStatusLabel("moving arm to side open-loop"); 00935 mech_interface_.attemptTrajectory(arm_name, 00936 object_manipulator::armConfigurations().trajectory(arm_name, "side"), false, 3.0); 00937 setStatusLabel("arm moved to side"); 00938 result.value = result.SUCCESS; 00939 } 00940 } 00941 break; 00942 case 1: //front 00943 { 00944 if (arm_planner_choice == 0) 00945 { 00946 setStatusLabel("moving arm to front using motion planner"); 00947 if ( !mech_interface_.attemptMoveArmToGoal(arm_name, object_manipulator::armConfigurations().position 00948 (arm_name, "front"), ord, pad) ) 00949 { 00950 setStatusLabel("failed to move arm to front (possible collisions)"); 00951 result.value = result.FAILED; 00952 } 00953 else 00954 { 00955 setStatusLabel("arm moved to front"); 00956 result.value = result.SUCCESS; 00957 } 00958 } 00959 else 00960 { 00961 setStatusLabel("moving arm to front open-loop"); 00962 mech_interface_.attemptTrajectory(arm_name, 00963 object_manipulator::armConfigurations().trajectory(arm_name, "front"), false, 3.0); 00964 setStatusLabel("arm moved to front"); 00965 result.value = result.SUCCESS; 00966 } 00967 } 00968 break; 00969 case 2: //side handoff 00970 { 00971 if (arm_planner_choice == 0) 00972 { 00973 setStatusLabel("moving arm to handoff using motion planner"); 00974 if ( !mech_interface_.attemptMoveArmToGoal(arm_name, 00975 object_manipulator::armConfigurations().position(arm_name, "handoff"), ord, pad) ) 00976 { 00977 setStatusLabel("failed to move arm to handoff (possible collisions)"); 00978 result.value = result.FAILED; 00979 } 00980 else 00981 { 00982 setStatusLabel("arm moved to handoff"); 00983 result.value = result.SUCCESS; 00984 } 00985 } 00986 else 00987 { 00988 setStatusLabel("moving arm to handoff open-loop"); 00989 mech_interface_.attemptTrajectory(arm_name, 00990 object_manipulator::armConfigurations().trajectory(arm_name, "handoff"), false, 3.0); 00991 setStatusLabel("arm moved to handoff"); 00992 result.value = result.SUCCESS; 00993 } 00994 } 00995 default: 00996 setStatusLabel("unknown operation requested"); 00997 } 00998 } 00999 catch (object_manipulator::ServiceNotFoundException &ex) 01000 { 01001 setStatusLabel("a needed service or action server was not found"); 01002 result.value = result.ERROR; 01003 } 01004 catch (object_manipulator::MoveArmStuckException &ex) 01005 { 01006 setStatusLabel("arm is stuck in a colliding position"); 01007 result.value = result.ERROR; 01008 } 01009 catch (object_manipulator::MissingParamException &ex) 01010 { 01011 setStatusLabel("parameters missing; is manipulation pipeline running?"); 01012 result.value = result.ERROR; 01013 } 01014 catch (object_manipulator::MechanismException &ex) 01015 { 01016 setStatusLabel("an error has occured, please call helpdesk"); 01017 result.value = result.ERROR; 01018 } 01019 catch (...) 01020 { 01021 setStatusLabel("an unknown error has occured, please call helpdesk"); 01022 result.value = result.ERROR; 01023 } 01024 } 01025 01026 void InteractiveManipulationBackend::openCloseGripper(pr2_object_manipulation_msgs::IMGUIOptions options) 01027 { 01028 std::string arm_name; 01029 if (options.arm_selection == 0) arm_name = "right_arm"; 01030 else arm_name = "left_arm"; 01031 double value = GripperController::GRIPPER_CLOSED + 01032 (GripperController::GRIPPER_OPEN - GripperController::GRIPPER_CLOSED) * 01033 (double)(options.gripper_slider_position)/100.0; 01034 bool result = gripper_controller_.commandGripperValue(arm_name, value); 01035 01036 //if opening the gripper, reset attached objects for that arm and reset the grasp info 01037 if (value > GripperController::GRIPPER_CLOSED + 01038 (GripperController::GRIPPER_OPEN - GripperController::GRIPPER_CLOSED)/2.) 01039 { 01040 mech_interface_.detachAllObjectsFromGripper(arm_name); 01041 getGraspInfo(arm_name)->reset(); 01042 } 01043 if (!result) setStatusLabel("failed to command gripper position"); 01044 else setStatusLabel("sent gripper position command"); 01045 } 01046 01047 int InteractiveManipulationBackend::modelObject(pr2_object_manipulation_msgs::IMGUIOptions options) 01048 { 01049 std::string arm_name; 01050 if (options.arm_selection == 0) arm_name = "right_arm"; 01051 else arm_name = "left_arm"; 01052 01053 //wait for collision map services 01054 setStatusLabel("waiting for collision map services..."); 01055 ros::Time start_time = ros::Time::now(); 01056 while (!collision_map_interface_.connectionsEstablished(ros::Duration(1.0)) && checkInterrupts() ) 01057 { 01058 if (ros::Time::now() - start_time >= ros::Duration(5.0)) 01059 { 01060 setStatusLabel("collision map services not found"); 01061 return object_manipulation_msgs::ManipulationResult::ERROR; 01062 } 01063 } 01064 01065 //create and send the goal 01066 bool keep_level = false; 01067 ROS_INFO("Modeling object in %s", arm_name.c_str()); 01068 pr2_create_object_model::ModelObjectInHandGoal goal; 01069 goal.arm_name = arm_name; 01070 goal.keep_level = keep_level; 01071 goal.clear_move.header.frame_id = "base_link"; 01072 goal.clear_move.vector.z = .5; 01073 goal.rotate_pose.header.frame_id = "torso_lift_link"; 01074 if(!keep_level) 01075 { 01076 goal.rotate_pose.pose.orientation.x = -0.5; 01077 if(arm_name == "right_arm") 01078 { 01079 goal.rotate_pose.pose.orientation.y = -0.5; 01080 goal.rotate_pose.pose.orientation.z = 0.5; 01081 } 01082 else 01083 { 01084 goal.rotate_pose.pose.orientation.y = 0.5; 01085 goal.rotate_pose.pose.orientation.z = -0.5; 01086 } 01087 goal.rotate_pose.pose.orientation.w = 0.5; 01088 } 01089 else 01090 { 01091 goal.rotate_pose = mech_interface_.getGripperPose(arm_name, "torso_lift_link"); 01092 } 01093 goal.rotate_pose.pose.position.x = .65; 01094 goal.rotate_pose.pose.position.z = .3; 01095 01096 goal.rotate_object = true; 01097 goal.add_to_collision_map = true; 01098 create_model_client_.client().sendGoal(goal); 01099 01100 setStatusLabel("calling model object in hand action..."); 01101 create_model_client_.waitForResult(); 01102 01103 if (create_model_client_.client().getState() == actionlib::SimpleClientGoalState::SUCCEEDED && 01104 !create_model_client_.client().getResult()->cluster.data.empty()) 01105 { 01106 setStatusLabel("modeling object in hand completed"); 01107 ROS_INFO("modeled object with collision name %s", 01108 create_model_client_.client().getResult()->collision_name.c_str()); 01109 object_manipulation_msgs::GraspableObject object; 01110 sensor_msgs::convertPointCloud2ToPointCloud( create_model_client_.client().getResult()->cluster, object.cluster ); 01111 object.reference_frame_id = create_model_client_.client().getResult()->cluster.header.frame_id; 01112 if (object.reference_frame_id != "r_wrist_roll_link" && 01113 object.reference_frame_id != "l_wrist_roll_link" ) 01114 { 01115 ROS_ERROR_STREAM("Object model expected in gripper frame and received in frame " << object.reference_frame_id); 01116 setStatusLabel("unexpected frame for modeled object"); 01117 return object_manipulation_msgs::ManipulationResult::ERROR; 01118 } 01119 01120 std::string arm_name; 01121 if ( options.arm_selection == 0) arm_name = "right_arm"; 01122 else arm_name = "left_arm"; 01123 getGraspInfo(arm_name)->object_ = object; 01124 //grasp is identity since object is in gripper frame 01125 getGraspInfo(arm_name)->grasp_.grasp_pose = GraspInfo::identityPose(); 01126 getGraspInfo(arm_name)->object_collision_name_ = create_model_client_.client().getResult()->collision_name; 01127 01128 return object_manipulation_msgs::ManipulationResult::SUCCESS; 01129 } 01130 else 01131 { 01132 setStatusLabel("modeling object in hand failed"); 01133 return object_manipulation_msgs::ManipulationResult::ERROR; 01134 } 01135 } 01136 01137 int InteractiveManipulationBackend::runScriptedAction(std::string action_name, std::string group_name, 01138 pr2_object_manipulation_msgs::IMGUIOptions options) 01139 { 01140 //setStatusLabel("Please select a point in the point cloud."); 01141 pr2_object_manipulation_msgs::RunScriptGoal goal; 01142 goal.action_name = action_name; 01143 goal.group_name = group_name; 01144 01145 run_script_client_.client().sendGoal(goal); 01146 run_script_client_.waitForResult(); 01147 01148 pr2_object_manipulation_msgs::RunScriptResult result = *(run_script_client_.client().getResult()); 01149 if (run_script_client_.client().getState() == actionlib::SimpleClientGoalState::SUCCEEDED) 01150 setStatusLabel(result.result); 01151 else 01152 setStatusLabel("Action failed."); 01153 return object_manipulation_msgs::ManipulationResult::SUCCESS; 01154 } 01155 01156 01157 01158 int InteractiveManipulationBackend::callGhostedGripper( const GetGripperPoseGoal &goal, GetGripperPoseResult &result) 01159 { 01160 get_gripper_pose_client_.client().sendGoal(goal); 01161 setStatusLabel("calling ghosted gripper click..."); 01162 get_gripper_pose_client_.waitForResult(); 01163 if (get_gripper_pose_client_.client().getState() != actionlib::SimpleClientGoalState::SUCCEEDED) 01164 { 01165 setStatusLabel("user has canceled"); 01166 return object_manipulation_msgs::ManipulationResult::CANCELLED; 01167 } 01168 result = *get_gripper_pose_client_.client().getResult(); 01169 return object_manipulation_msgs::ManipulationResult::SUCCESS; 01170 } 01171 01172 int InteractiveManipulationBackend::callGhostedGripperPickup( std::string arm_name, 01173 object_manipulation_msgs::Grasp &grasp ) 01174 { 01175 GetGripperPoseResult result; 01176 GetGripperPoseGoal goal; 01177 goal.arm_name = arm_name; 01178 int success = callGhostedGripper(goal, result); 01179 if (success != object_manipulation_msgs::ManipulationResult::SUCCESS) return success; 01180 //convert from gripper opening to joint angle 01181 result.gripper_opening = result.gripper_opening * 0.5 / 0.0857; 01182 if (!getGrasp(grasp, arm_name, result.gripper_pose, result.gripper_opening)) 01183 { 01184 ROS_DEBUG("getGrasp returned ERROR"); 01185 return object_manipulation_msgs::ManipulationResult::ERROR; 01186 } 01187 return object_manipulation_msgs::ManipulationResult::SUCCESS; 01188 } 01189 01190 int InteractiveManipulationBackend::callGhostedGripperMove( std::string arm_name, 01191 geometry_msgs::PoseStamped &location ) 01192 { 01193 GetGripperPoseResult result; 01194 GetGripperPoseGoal goal; 01195 goal.arm_name = arm_name; 01196 goal.object = getGraspInfo(arm_name)->object_; 01197 goal.grasp = getGraspInfo(arm_name)->grasp_; 01198 int success = callGhostedGripper(goal, result); 01199 if (success != object_manipulation_msgs::ManipulationResult::SUCCESS) return success; 01200 location = result.gripper_pose; 01201 return object_manipulation_msgs::ManipulationResult::SUCCESS; 01202 } 01203 01204 void InteractiveManipulationBackend::imageClickCallback(const pr2_object_manipulation_msgs::ImageClickConstPtr &click) 01205 { 01206 geometry_msgs::PointStamped target; 01207 target.header.frame_id = click->ray.header.frame_id; 01208 target.point.x = click->ray.origin.x + click->ray.direction.x; 01209 target.point.y = click->ray.origin.y + click->ray.direction.y; 01210 target.point.z = click->ray.origin.z + click->ray.direction.z; 01211 //should get the right pointing frame, maybe from a param or maybe from the message 01212 try 01213 { 01214 if ( !mech_interface_.pointHeadAction( target, click->camera_frame_id ) ) 01215 { 01216 setStatusLabel( "head movement failed"); 01217 } 01218 else setStatusLabel( "head movement completed"); 01219 } 01220 catch (object_manipulator::ServiceNotFoundException &ex) 01221 { 01222 setStatusLabel("a needed service or action server was not found"); 01223 } 01224 } 01225 01226 void InteractiveManipulationBackend::lookAtTable() 01227 { 01228 geometry_msgs::PointStamped target; 01229 target.point.x = 1; 01230 target.point.y = 0; 01231 target.point.z = 0; 01232 target.header.frame_id = "base_link"; 01233 setStatusLabel( "moving head" ); 01234 try 01235 { 01236 if ( !mech_interface_.pointHeadAction( target, "/narrow_stereo_optical_frame" ) ) 01237 { 01238 setStatusLabel( "head movement failed"); 01239 } 01240 else setStatusLabel( "head movement completed"); 01241 } 01242 catch (object_manipulator::ServiceNotFoundException &ex) 01243 { 01244 setStatusLabel("a needed service or action server was not found"); 01245 } 01246 } 01247 01248 01249 } 01250