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
00031
00032
00033
00034
00035
00036 #include "object_manipulator/object_manipulator.h"
00037
00038 #include <algorithm>
00039
00040
00041
00042
00043
00044
00045
00046 #include <object_manipulation_msgs/tools.h>
00047
00048 #include "object_manipulator/grasp_execution/approach_lift_grasp.h"
00049 #include "object_manipulator/grasp_execution/grasp_tester_fast.h"
00050 #include "object_manipulator/place_execution/descend_retreat_place.h"
00051 #include "object_manipulator/place_execution/place_tester_fast.h"
00052
00053 #include "object_manipulator/tools/grasp_marker_publisher.h"
00054 #include "object_manipulator/tools/exceptions.h"
00055
00056 using object_manipulation_msgs::PickupGoal;
00057 using object_manipulation_msgs::PickupResult;
00058 using object_manipulation_msgs::PickupFeedback;
00059 using object_manipulation_msgs::PlaceGoal;
00060 using object_manipulation_msgs::PlaceResult;
00061 using object_manipulation_msgs::PlaceFeedback;
00062 using object_manipulation_msgs::ManipulationResult;
00063 using object_manipulation_msgs::GraspResult;
00064 using object_manipulation_msgs::PlaceLocationResult;
00065 using object_manipulation_msgs::getGraspResultInfo;
00066 using object_manipulation_msgs::getPlaceLocationResultInfo;
00067 using manipulation_msgs::Grasp;
00068 using manipulation_msgs::GraspPlanningAction;
00069 using manipulation_msgs::GraspableObject;
00070
00071 namespace object_manipulator {
00072
00073 ObjectManipulator::ObjectManipulator() :
00074 priv_nh_("~"),
00075 root_nh_(""),
00076 grasp_planning_actions_("", "", false, false),
00077 marker_pub_(NULL)
00078 {
00079 bool publish_markers = true;
00080 if (publish_markers)
00081 {
00082 marker_pub_ = new GraspMarkerPublisher();
00083 }
00084
00085 priv_nh_.param<std::string>("kinematics_plugin_name", kinematics_plugin_name_, "pr2_arm_kinematics/PR2ArmKinematicsPlugin");
00086
00087 grasp_tester_with_approach_ = new GraspTesterWithApproach;
00088 grasp_tester_with_approach_->setMarkerPublisher(marker_pub_);
00089 grasp_tester_fast_ = new GraspTesterFast(NULL, kinematics_plugin_name_);
00090 grasp_tester_fast_->setMarkerPublisher(marker_pub_);
00091 unsafe_grasp_tester_ = new UnsafeGraspTester;
00092 unsafe_grasp_tester_->setMarkerPublisher(marker_pub_);
00093 standard_grasp_performer_ = new StandardGraspPerformer;
00094 standard_grasp_performer_->setMarkerPublisher(marker_pub_);
00095 reactive_grasp_performer_ = new ReactiveGraspPerformer;
00096 reactive_grasp_performer_->setMarkerPublisher(marker_pub_);
00097 unsafe_grasp_performer_ = new UnsafeGraspPerformer;
00098 unsafe_grasp_performer_->setMarkerPublisher(marker_pub_);
00099
00100 standard_place_tester_ = new PlaceTesterFast(NULL, kinematics_plugin_name_);
00101 standard_place_tester_->setMarkerPublisher(marker_pub_);
00102 standard_place_performer_ = new StandardPlacePerformer;
00103 standard_place_performer_->setMarkerPublisher(marker_pub_);
00104 reactive_place_performer_ = new ReactivePlacePerformer;
00105 reactive_place_performer_->setMarkerPublisher(marker_pub_);
00106
00107 priv_nh_.param<std::string>("default_cluster_planner", default_cluster_planner_, "default_cluster_planner");
00108 priv_nh_.param<std::string>("default_database_planner", default_database_planner_, "default_database_planner");
00109 priv_nh_.param<std::string>("default_probabilistic_planner", default_probabilistic_planner_,
00110 "default_probabilistic_planner");
00111 priv_nh_.param<bool>("use_probabilistic_grasp_planner", use_probabilistic_planner_, false);
00112 priv_nh_.param<bool>("randomize_grasps", randomize_grasps_, false);
00113
00114 ROS_INFO("Object manipulator ready. Default cluster planner: %s. Default database planner: %s.",
00115 default_cluster_planner_.c_str(), default_database_planner_.c_str());
00116 if(use_probabilistic_planner_)
00117 {
00118 ROS_INFO("Probabilistic planner enabled");
00119 }
00120 ROS_INFO_NAMED("manipulation","Object manipulator ready");
00121 }
00122
00123 ObjectManipulator::~ObjectManipulator()
00124 {
00125 delete marker_pub_;
00126
00127 delete grasp_tester_fast_;
00128 delete grasp_tester_with_approach_;
00129 delete unsafe_grasp_tester_;
00130 delete standard_grasp_performer_;
00131 delete reactive_grasp_performer_;
00132 delete unsafe_grasp_performer_;
00133
00134 delete standard_place_tester_;
00135 delete standard_place_performer_;
00136 delete reactive_place_performer_;
00137 }
00138
00139 void ObjectManipulator::graspFeedback(
00140 actionlib::SimpleActionServer<object_manipulation_msgs::PickupAction> *action_server,
00141 size_t tested_grasps, size_t current_grasp)
00142 {
00143 PickupFeedback feedback;
00144 feedback.total_grasps = grasp_container_.size();
00145 feedback.current_grasp = current_grasp + tested_grasps;
00146 action_server->publishFeedback(feedback);
00147 }
00148
00149 void ObjectManipulator::graspPlanningFeedbackCallback(
00150 const manipulation_msgs::GraspPlanningFeedbackConstPtr &feedback)
00151 {
00152 ROS_DEBUG_STREAM_NAMED("manipulation", "Feedback from planning action, total grasps: " << feedback->grasps.size());
00153 grasp_container_.addGrasps(feedback->grasps);
00154 }
00155
00156 void ObjectManipulator::graspPlanningDoneCallback(const actionlib::SimpleClientGoalState& state,
00157 const manipulation_msgs::GraspPlanningResultConstPtr &result)
00158 {
00159 if (state == actionlib::SimpleClientGoalState::SUCCEEDED)
00160 {
00161 ROS_DEBUG_STREAM_NAMED("manipulation", "Final result from planning action, total grasps: " << result->grasps.size());
00162 grasp_container_.addGrasps(result->grasps);
00163 }
00164 else
00165 {
00166 ROS_ERROR("Grasp planning action did not succeed");
00167 }
00168 }
00169
00170 void ObjectManipulator::pickup(const PickupGoal::ConstPtr &pickup_goal,
00171 actionlib::SimpleActionServer<object_manipulation_msgs::PickupAction> *action_server)
00172 {
00173
00174 PickupResult result;
00175
00176
00177
00178
00179
00180 if ( pickup_goal->target.cluster.points.size() > 0)
00181 {
00182 for (size_t i=0; i<pickup_goal->target.potential_models.size(); i++)
00183 {
00184 if ( pickup_goal->target.potential_models[i].pose.header.frame_id != pickup_goal->target.cluster.header.frame_id)
00185 {
00186 ROS_ERROR("Target object recognition result(s) not in the same frame as the cluster");
00187 result.manipulation_result.value = ManipulationResult::ERROR;
00188 action_server->setAborted(result);
00189 return;
00190 }
00191 }
00192 }
00193
00194
00195 grasp_container_.clear();
00196 bool using_planner_action;
00197 std::string planner_action;
00198 if (!pickup_goal->desired_grasps.empty())
00199 {
00200
00201 grasp_container_.addGrasps(pickup_goal->desired_grasps);
00202 using_planner_action = false;
00203 }
00204 else
00205 {
00206 if (use_probabilistic_planner_)
00207 {
00208 ROS_INFO("Using probabilistic planner");
00209
00210 planner_action = default_probabilistic_planner_;
00211 }
00212 else
00213 {
00214
00215 if (!pickup_goal->target.potential_models.empty())
00216 planner_action = default_database_planner_;
00217 else
00218 planner_action = default_cluster_planner_;
00219 }
00220
00221
00222 manipulation_msgs::GraspPlanningGoal goal;
00223 goal.arm_name = pickup_goal->arm_name;
00224 goal.target = pickup_goal->target;
00225 goal.collision_object_name = pickup_goal->collision_object_name;
00226 goal.collision_support_surface_name = pickup_goal->collision_support_surface_name;
00227 goal.movable_obstacles = pickup_goal->movable_obstacles;
00228 try
00229 {
00230 grasp_planning_actions_.client(planner_action).sendGoal(goal,
00231 boost::bind(&ObjectManipulator::graspPlanningDoneCallback, this, _1, _2),
00232 actionlib::SimpleActionClient<GraspPlanningAction>::SimpleActiveCallback(),
00233 boost::bind(&ObjectManipulator::graspPlanningFeedbackCallback, this, _1));
00234 }
00235 catch (ServiceNotFoundException &ex)
00236 {
00237 ROS_ERROR("Planning action %s not found", planner_action.c_str());
00238 result.manipulation_result.value = ManipulationResult::ERROR;
00239 action_server->setAborted(result);
00240 return;
00241 }
00242 using_planner_action = true;
00243 }
00244 ScopedGoalCancel<GraspPlanningAction> goal_cancel(NULL);
00245 if (using_planner_action)
00246 {
00247 goal_cancel.setClient(&grasp_planning_actions_.client(planner_action));
00248 }
00249
00250 GraspTester *grasp_tester;
00251 GraspPerformer *grasp_performer;
00252 if (pickup_goal->ignore_collisions)
00253 {
00254 grasp_tester = unsafe_grasp_tester_;
00255 grasp_performer = unsafe_grasp_performer_;
00256 }
00257 else
00258 {
00259
00260 grasp_tester = grasp_tester_fast_;
00261 if (pickup_goal->use_reactive_execution)
00262 {
00263 grasp_performer = reactive_grasp_performer_;
00264 }
00265 else
00266 {
00267 grasp_performer = standard_grasp_performer_;
00268 }
00269 }
00270
00271 grasp_tester->setInterruptFunction(
00272 boost::bind(&actionlib::SimpleActionServer<object_manipulation_msgs::PickupAction>::isPreemptRequested,
00273 action_server));
00274 grasp_performer->setInterruptFunction(
00275 boost::bind(&actionlib::SimpleActionServer<object_manipulation_msgs::PickupAction>::isPreemptRequested,
00276 action_server));
00277
00278
00279
00280
00281 ros::WallDuration dur(0.5);
00282 dur.sleep();
00283
00284 arm_navigation_msgs::OrderedCollisionOperations emp_coll;
00285 std::vector<arm_navigation_msgs::LinkPadding> link_padding;
00286 mechInterface().getPlanningScene(emp_coll, link_padding);
00287
00288 ros::WallTime start = ros::WallTime::now();
00289
00290
00291 result.manipulation_result.value = ManipulationResult::UNFEASIBLE;
00292 try
00293 {
00294 size_t tested_grasps = 0;
00295 while (1)
00296 {
00297 if (action_server->isPreemptRequested()) throw InterruptRequestedException();
00298
00299 ROS_DEBUG_STREAM_NAMED("manipulation", "Object manipulator: getting grasps beyond " << tested_grasps);
00300 std::vector<manipulation_msgs::Grasp> new_grasps = grasp_container_.getGrasps(tested_grasps);
00301 if ( new_grasps.empty() )
00302 {
00303 if ( using_planner_action && (grasp_planning_actions_.client(planner_action).getState() ==
00304 actionlib::SimpleClientGoalState::ACTIVE ||
00305 grasp_planning_actions_.client(planner_action).getState() ==
00306 actionlib::SimpleClientGoalState::PENDING) )
00307 {
00308 ROS_DEBUG_NAMED("manipulation", "Object manipulator: waiting for planner action to provide grasps");
00309 ros::Duration(0.25).sleep();
00310 continue;
00311 }
00312 else
00313 {
00314 ROS_INFO("Object manipulator: all grasps have been tested");
00315 break;
00316 }
00317 }
00318 grasp_tester->setFeedbackFunction(boost::bind(&ObjectManipulator::graspFeedback,
00319 this, action_server, tested_grasps, _1));
00320
00321 ROS_DEBUG_STREAM_NAMED("manipulation", "Object manipulator: testing a new batch of " << new_grasps.size() << " grasps");
00322 std::vector<GraspExecutionInfo> execution_info;
00323 grasp_tester->testGrasps(*pickup_goal, new_grasps, execution_info, !pickup_goal->only_perform_feasibility_test);
00324 if (execution_info.empty()) throw GraspException("grasp tester provided empty ExecutionInfo");
00325 if (execution_info.empty()) throw GraspException("grasp tester provided empty ExecutionInfo");
00326
00327 if (!pickup_goal->only_perform_feasibility_test)
00328 {
00329 ROS_DEBUG_NAMED("manipulation", "Attempting to perform grasps");
00330 grasp_performer->performGrasps(*pickup_goal, new_grasps, execution_info);
00331 }
00332 if (execution_info.empty()) throw GraspException("grasp performer provided empty ExecutionInfo");
00333
00334 for (size_t i=0; i<execution_info.size(); i++)
00335 {
00336 result.attempted_grasps.push_back(new_grasps[i]);
00337 result.attempted_grasp_results.push_back(execution_info[i].result_);
00338 }
00339
00340 if (execution_info.back().result_.result_code == GraspResult::SUCCESS)
00341 {
00342 result.manipulation_result.value = ManipulationResult::SUCCESS;
00343 if (!pickup_goal->only_perform_feasibility_test)
00344 {
00345 ROS_DEBUG_NAMED("manipulation", "Grasp reports success");
00346 result.grasp = new_grasps.at( execution_info.size() -1 );
00347 action_server->setSucceeded(result);
00348 return;
00349 }
00350 }
00351
00352 if (!execution_info.back().result_.continuation_possible)
00353 {
00354 if (pickup_goal->only_perform_feasibility_test)
00355 {
00356 ROS_ERROR("Continuation impossible when performing feasibility test");
00357 }
00358 result.grasp = new_grasps.at( execution_info.size() -1 );
00359 if (execution_info.back().result_.result_code == GraspResult::LIFT_FAILED)
00360 result.manipulation_result.value = ManipulationResult::LIFT_FAILED;
00361 else
00362 result.manipulation_result.value = ManipulationResult::FAILED;
00363 action_server->setAborted(result);
00364 return;
00365 }
00366
00367 tested_grasps += execution_info.size();
00368 }
00369
00370 if (pickup_goal->only_perform_feasibility_test && result.manipulation_result.value == ManipulationResult::SUCCESS)
00371 {
00372 action_server->setSucceeded(result);
00373 }
00374 else
00375 {
00376 action_server->setAborted(result);
00377 }
00378 return;
00379 }
00380 catch (InterruptRequestedException &ex)
00381 {
00382 ROS_DEBUG_NAMED("manipulation","Pickup goal preempted");
00383 action_server->setPreempted();
00384 return;
00385 }
00386 catch (MoveArmStuckException &ex)
00387 {
00388 ROS_ERROR("Grasp aborted because move_arm is stuck");
00389 result.manipulation_result.value = ManipulationResult::ARM_MOVEMENT_PREVENTED;
00390 action_server->setAborted(result);
00391 return;
00392 }
00393 catch (GraspException &ex)
00394 {
00395 ROS_ERROR("Grasp error; exception: %s", ex.what());
00396 result.manipulation_result.value = ManipulationResult::ERROR;
00397 action_server->setAborted(result);
00398 return;
00399 }
00400 }
00401
00402 void ObjectManipulator::placeFeedback(
00403 actionlib::SimpleActionServer<object_manipulation_msgs::PlaceAction> *action_server,
00404 size_t tested_places, size_t total_places, size_t current_place)
00405 {
00406 PlaceFeedback feedback;
00407 feedback.total_locations = total_places;
00408 feedback.current_location = current_place + tested_places;
00409 action_server->publishFeedback(feedback);
00410 }
00411
00412 void ObjectManipulator::place(const object_manipulation_msgs::PlaceGoal::ConstPtr &place_goal,
00413 actionlib::SimpleActionServer<object_manipulation_msgs::PlaceAction> *action_server)
00414 {
00415 PlaceResult result;
00416 PlaceTester *place_tester = standard_place_tester_;
00417 PlacePerformer *place_performer = standard_place_performer_;
00418 if (place_goal->use_reactive_place) place_performer = reactive_place_performer_;
00419
00420 place_tester->setInterruptFunction(
00421 boost::bind(&actionlib::SimpleActionServer<object_manipulation_msgs::PlaceAction>::isPreemptRequested,
00422 action_server));
00423 place_performer->setInterruptFunction(
00424 boost::bind(&actionlib::SimpleActionServer<object_manipulation_msgs::PlaceAction>::isPreemptRequested,
00425 action_server));
00426
00427 std::vector<geometry_msgs::PoseStamped> place_locations = place_goal->place_locations;
00428 try
00429 {
00430 std::vector<PlaceExecutionInfo> execution_info;
00431 result.manipulation_result.value = ManipulationResult::UNFEASIBLE;
00432 size_t tested_places = 0;
00433 while (!place_locations.empty())
00434 {
00435 if (action_server->isPreemptRequested()) throw InterruptRequestedException();
00436 place_tester->setFeedbackFunction(boost::bind(&ObjectManipulator::placeFeedback,
00437 this, action_server, tested_places, place_locations.size(), _1));
00438
00439 place_tester->testPlaces(*place_goal, place_locations, execution_info,
00440 !place_goal->only_perform_feasibility_test);
00441 if (execution_info.empty()) throw GraspException("place tester provided empty ExecutionInfo");
00442
00443 if (!place_goal->only_perform_feasibility_test)
00444 {
00445 place_performer->performPlaces(*place_goal, place_locations, execution_info);
00446 }
00447 if (execution_info.empty()) throw GraspException("place performer provided empty ExecutionInfo");
00448
00449 std::vector<geometry_msgs::PoseStamped>::iterator it = place_locations.begin();
00450 for (size_t i=0; i<execution_info.size(); i++)
00451 {
00452 result.attempted_locations.push_back(place_locations[i]);
00453 result.attempted_location_results.push_back(execution_info[i].result_);
00454 it++;
00455 }
00456
00457 if (execution_info.back().result_.result_code == PlaceLocationResult::SUCCESS)
00458 {
00459 result.manipulation_result.value = ManipulationResult::SUCCESS;
00460 if (!place_goal->only_perform_feasibility_test)
00461 {
00462 result.place_location = place_locations.at( execution_info.size() - 1 );
00463 action_server->setSucceeded(result);
00464 return;
00465 }
00466 }
00467
00468 if (!execution_info.back().result_.continuation_possible)
00469 {
00470 if (place_goal->only_perform_feasibility_test)
00471 {
00472 ROS_ERROR("Continuation impossible when performing feasibility test");
00473 }
00474 result.place_location = place_locations.at( execution_info.size() - 1 );
00475 if (execution_info.back().result_.result_code == PlaceLocationResult::RETREAT_FAILED)
00476 result.manipulation_result.value = ManipulationResult::RETREAT_FAILED;
00477 else
00478 result.manipulation_result.value = ManipulationResult::FAILED;
00479 action_server->setAborted(result);
00480 return;
00481 }
00482
00483 tested_places += execution_info.size();
00484 execution_info.clear();
00485 place_locations.erase(place_locations.begin(), it);
00486 }
00487
00488 if (place_goal->only_perform_feasibility_test && result.manipulation_result.value == ManipulationResult::SUCCESS)
00489 {
00490 action_server->setSucceeded(result);
00491 }
00492 else
00493 {
00494 action_server->setAborted(result);
00495 }
00496 return;
00497 }
00498 catch (InterruptRequestedException &ex)
00499 {
00500 ROS_DEBUG_NAMED("manipulation","Place goal preempted");
00501 action_server->setPreempted();
00502 return;
00503 }
00504 catch (MoveArmStuckException &ex)
00505 {
00506 ROS_ERROR("Place aborted because move_arm is stuck");
00507 result.manipulation_result.value = ManipulationResult::ARM_MOVEMENT_PREVENTED;
00508 action_server->setAborted(result);
00509 return;
00510 }
00511 catch (GraspException &ex)
00512 {
00513 ROS_ERROR("Place error; exception: %s", ex.what());
00514 result.manipulation_result.value = ManipulationResult::ERROR;
00515 action_server->setAborted(result);
00516 return;
00517 }
00518 }
00519
00520 }
00521