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