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
00037 #include "pick_place_action_capability.h"
00038 #include <moveit/plan_execution/plan_execution.h>
00039 #include <moveit/plan_execution/plan_with_sensing.h>
00040 #include <moveit/move_group_pick_place_capability/capability_names.h>
00041
00042 #include <manipulation_msgs/GraspPlanning.h>
00043 #include <eigen_conversions/eigen_msg.h>
00044
00045 move_group::MoveGroupPickPlaceAction::MoveGroupPickPlaceAction() :
00046 MoveGroupCapability("PickPlaceAction"),
00047 pickup_state_(IDLE)
00048 {
00049 }
00050
00051 void move_group::MoveGroupPickPlaceAction::initialize()
00052 {
00053 pick_place_.reset(new pick_place::PickPlace(context_->planning_pipeline_));
00054 pick_place_->displayComputedMotionPlans(true);
00055
00056 if (context_->debug_)
00057 pick_place_->displayProcessedGrasps(true);
00058
00059
00060 pickup_action_server_.reset(new actionlib::SimpleActionServer<moveit_msgs::PickupAction>(root_node_handle_, PICKUP_ACTION,
00061 boost::bind(&MoveGroupPickPlaceAction::executePickupCallback, this, _1), false));
00062 pickup_action_server_->registerPreemptCallback(boost::bind(&MoveGroupPickPlaceAction::preemptPickupCallback, this));
00063 pickup_action_server_->start();
00064
00065
00066 place_action_server_.reset(new actionlib::SimpleActionServer<moveit_msgs::PlaceAction>(root_node_handle_, PLACE_ACTION,
00067 boost::bind(&MoveGroupPickPlaceAction::executePlaceCallback, this, _1), false));
00068 place_action_server_->registerPreemptCallback(boost::bind(&MoveGroupPickPlaceAction::preemptPlaceCallback, this));
00069 place_action_server_->start();
00070
00071 grasp_planning_service_ = root_node_handle_.serviceClient<manipulation_msgs::GraspPlanning>("database_grasp_planning");
00072 }
00073
00074 void move_group::MoveGroupPickPlaceAction::startPickupExecutionCallback()
00075 {
00076 setPickupState(MONITOR);
00077 }
00078
00079 void move_group::MoveGroupPickPlaceAction::startPickupLookCallback()
00080 {
00081 setPickupState(LOOK);
00082 }
00083
00084 void move_group::MoveGroupPickPlaceAction::startPlaceExecutionCallback()
00085 {
00086 setPlaceState(MONITOR);
00087 }
00088
00089 void move_group::MoveGroupPickPlaceAction::startPlaceLookCallback()
00090 {
00091 setPlaceState(LOOK);
00092 }
00093
00094 void move_group::MoveGroupPickPlaceAction::executePickupCallback_PlanOnly(const moveit_msgs::PickupGoalConstPtr& goal, moveit_msgs::PickupResult &action_res)
00095 {
00096 pick_place::PickPlanPtr plan;
00097 try
00098 {
00099 planning_scene_monitor::LockedPlanningSceneRO ps(context_->planning_scene_monitor_);
00100 plan = pick_place_->planPick(ps, *goal);
00101 }
00102 catch(std::runtime_error &ex)
00103 {
00104 ROS_ERROR("Pick&place threw an exception: %s", ex.what());
00105 }
00106 catch(...)
00107 {
00108 ROS_ERROR("Pick&place threw an exception");
00109 }
00110
00111 if (plan)
00112 {
00113 const std::vector<pick_place::ManipulationPlanPtr> &success = plan->getSuccessfulManipulationPlans();
00114 if (success.empty())
00115 {
00116 action_res.error_code = plan->getErrorCode();
00117 }
00118 else
00119 {
00120 const pick_place::ManipulationPlanPtr &result = success.back();
00121 convertToMsg(result->trajectories_, action_res.trajectory_start, action_res.trajectory_stages);
00122 action_res.trajectory_descriptions.resize(result->trajectories_.size());
00123 for (std::size_t i = 0 ; i < result->trajectories_.size() ; ++i)
00124 action_res.trajectory_descriptions[i] = result->trajectories_[i].description_;
00125 if (result->id_ < goal->possible_grasps.size())
00126 action_res.grasp = goal->possible_grasps[result->id_];
00127 action_res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00128 }
00129 }
00130 else
00131 {
00132 action_res.error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
00133 }
00134 }
00135
00136 void move_group::MoveGroupPickPlaceAction::executePlaceCallback_PlanOnly(const moveit_msgs::PlaceGoalConstPtr& goal, moveit_msgs::PlaceResult &action_res)
00137 {
00138 pick_place::PlacePlanPtr plan;
00139 try
00140 {
00141 planning_scene_monitor::LockedPlanningSceneRO ps(context_->planning_scene_monitor_);
00142 plan = pick_place_->planPlace(ps, *goal);
00143 }
00144 catch(std::runtime_error &ex)
00145 {
00146 ROS_ERROR("Pick&place threw an exception: %s", ex.what());
00147 }
00148 catch(...)
00149 {
00150 ROS_ERROR("Pick&place threw an exception");
00151 }
00152
00153 if (plan)
00154 {
00155 const std::vector<pick_place::ManipulationPlanPtr> &success = plan->getSuccessfulManipulationPlans();
00156 if (success.empty())
00157 {
00158 action_res.error_code = plan->getErrorCode();
00159 }
00160 else
00161 {
00162 const pick_place::ManipulationPlanPtr &result = success.back();
00163 convertToMsg(result->trajectories_, action_res.trajectory_start, action_res.trajectory_stages);
00164 action_res.trajectory_descriptions.resize(result->trajectories_.size());
00165 for (std::size_t i = 0 ; i < result->trajectories_.size() ; ++i)
00166 action_res.trajectory_descriptions[i] = result->trajectories_[i].description_;
00167 if (result->id_ < goal->place_locations.size())
00168 action_res.place_location = goal->place_locations[result->id_];
00169 action_res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00170 }
00171 }
00172 else
00173 {
00174 action_res.error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE;
00175 }
00176 }
00177
00178 bool move_group::MoveGroupPickPlaceAction::planUsingPickPlace_Pickup(const moveit_msgs::PickupGoal& goal, moveit_msgs::PickupResult *action_res,
00179 plan_execution::ExecutableMotionPlan &plan)
00180 {
00181 setPickupState(PLANNING);
00182
00183 planning_scene_monitor::LockedPlanningSceneRO ps(plan.planning_scene_monitor_);
00184
00185 pick_place::PickPlanPtr pick_plan;
00186 try
00187 {
00188 pick_plan = pick_place_->planPick(plan.planning_scene_, goal);
00189 }
00190 catch(std::runtime_error &ex)
00191 {
00192 ROS_ERROR("Pick&place threw an exception: %s", ex.what());
00193 }
00194 catch(...)
00195 {
00196 ROS_ERROR("Pick&place threw an exception");
00197 }
00198
00199 if (pick_plan)
00200 {
00201 const std::vector<pick_place::ManipulationPlanPtr> &success = pick_plan->getSuccessfulManipulationPlans();
00202 if (success.empty())
00203 {
00204 plan.error_code_ = pick_plan->getErrorCode();
00205 }
00206 else
00207 {
00208 const pick_place::ManipulationPlanPtr &result = success.back();
00209 plan.plan_components_ = result->trajectories_;
00210 if (result->id_ < goal.possible_grasps.size())
00211 action_res->grasp = goal.possible_grasps[result->id_];
00212 plan.error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00213 }
00214 }
00215 else
00216 {
00217 plan.error_code_.val = moveit_msgs::MoveItErrorCodes::FAILURE;
00218 }
00219
00220 return plan.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS;
00221 }
00222
00223 bool move_group::MoveGroupPickPlaceAction::planUsingPickPlace_Place(const moveit_msgs::PlaceGoal& goal, moveit_msgs::PlaceResult *action_res,
00224 plan_execution::ExecutableMotionPlan &plan)
00225 {
00226 setPlaceState(PLANNING);
00227
00228 planning_scene_monitor::LockedPlanningSceneRO ps(plan.planning_scene_monitor_);
00229
00230 pick_place::PlacePlanPtr place_plan;
00231 try
00232 {
00233 place_plan = pick_place_->planPlace(plan.planning_scene_, goal);
00234 }
00235 catch(std::runtime_error &ex)
00236 {
00237 ROS_ERROR("Pick&place threw an exception: %s", ex.what());
00238 }
00239 catch(...)
00240 {
00241 ROS_ERROR("Pick&place threw an exception");
00242 }
00243
00244 if (place_plan)
00245 {
00246 const std::vector<pick_place::ManipulationPlanPtr> &success = place_plan->getSuccessfulManipulationPlans();
00247 if (success.empty())
00248 {
00249 plan.error_code_ = place_plan->getErrorCode();
00250 }
00251 else
00252 {
00253 const pick_place::ManipulationPlanPtr &result = success.back();
00254 plan.plan_components_ = result->trajectories_;
00255 if (result->id_ < goal.place_locations.size())
00256 action_res->place_location = goal.place_locations[result->id_];
00257 plan.error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00258 }
00259 }
00260 else
00261 {
00262 plan.error_code_.val = moveit_msgs::MoveItErrorCodes::FAILURE;
00263 }
00264
00265 return plan.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS;
00266 }
00267
00268 void move_group::MoveGroupPickPlaceAction::executePickupCallback_PlanAndExecute(const moveit_msgs::PickupGoalConstPtr& goal, moveit_msgs::PickupResult &action_res)
00269 {
00270 plan_execution::PlanExecution::Options opt;
00271
00272 opt.replan_ = goal->planning_options.replan;
00273 opt.replan_attempts_ = goal->planning_options.replan_attempts;
00274 opt.replan_delay_ = goal->planning_options.replan_delay;
00275 opt.before_execution_callback_ = boost::bind(&MoveGroupPickPlaceAction::startPickupExecutionCallback, this);
00276
00277 opt.plan_callback_ = boost::bind(&MoveGroupPickPlaceAction::planUsingPickPlace_Pickup, this, boost::cref(*goal), &action_res, _1);
00278 if (goal->planning_options.look_around && context_->plan_with_sensing_)
00279 {
00280 opt.plan_callback_ = boost::bind(&plan_execution::PlanWithSensing::computePlan, context_->plan_with_sensing_.get(), _1, opt.plan_callback_,
00281 goal->planning_options.look_around_attempts, goal->planning_options.max_safe_execution_cost);
00282 context_->plan_with_sensing_->setBeforeLookCallback(boost::bind(&MoveGroupPickPlaceAction::startPickupLookCallback, this));
00283 }
00284
00285 plan_execution::ExecutableMotionPlan plan;
00286 context_->plan_execution_->planAndExecute(plan, goal->planning_options.planning_scene_diff, opt);
00287
00288 convertToMsg(plan.plan_components_, action_res.trajectory_start, action_res.trajectory_stages);
00289 action_res.trajectory_descriptions.resize(plan.plan_components_.size());
00290 for (std::size_t i = 0 ; i < plan.plan_components_.size() ; ++i)
00291 action_res.trajectory_descriptions[i] = plan.plan_components_[i].description_;
00292 action_res.error_code = plan.error_code_;
00293 }
00294
00295 void move_group::MoveGroupPickPlaceAction::executePlaceCallback_PlanAndExecute(const moveit_msgs::PlaceGoalConstPtr& goal, moveit_msgs::PlaceResult &action_res)
00296 {
00297 plan_execution::PlanExecution::Options opt;
00298
00299 opt.replan_ = goal->planning_options.replan;
00300 opt.replan_attempts_ = goal->planning_options.replan_attempts;
00301 opt.replan_delay_ = goal->planning_options.replan_delay;
00302 opt.before_execution_callback_ = boost::bind(&MoveGroupPickPlaceAction::startPlaceExecutionCallback, this);
00303 opt.plan_callback_ = boost::bind(&MoveGroupPickPlaceAction::planUsingPickPlace_Place, this, boost::cref(*goal), &action_res, _1);
00304 if (goal->planning_options.look_around && context_->plan_with_sensing_)
00305 {
00306 opt.plan_callback_ = boost::bind(&plan_execution::PlanWithSensing::computePlan, context_->plan_with_sensing_.get(), _1, opt.plan_callback_,
00307 goal->planning_options.look_around_attempts, goal->planning_options.max_safe_execution_cost);
00308 context_->plan_with_sensing_->setBeforeLookCallback(boost::bind(&MoveGroupPickPlaceAction::startPlaceLookCallback, this));
00309 }
00310
00311 plan_execution::ExecutableMotionPlan plan;
00312 context_->plan_execution_->planAndExecute(plan, goal->planning_options.planning_scene_diff, opt);
00313
00314 convertToMsg(plan.plan_components_, action_res.trajectory_start, action_res.trajectory_stages);
00315 action_res.trajectory_descriptions.resize(plan.plan_components_.size());
00316 for (std::size_t i = 0 ; i < plan.plan_components_.size() ; ++i)
00317 action_res.trajectory_descriptions[i] = plan.plan_components_[i].description_;
00318 action_res.error_code = plan.error_code_;
00319 }
00320
00321 void move_group::MoveGroupPickPlaceAction::executePickupCallback(const moveit_msgs::PickupGoalConstPtr& input_goal)
00322 {
00323 setPickupState(PLANNING);
00324
00325 context_->planning_scene_monitor_->updateFrameTransforms();
00326
00327 moveit_msgs::PickupGoalConstPtr goal;
00328 if (input_goal->possible_grasps.empty())
00329 {
00330 moveit_msgs::PickupGoal* copy(new moveit_msgs::PickupGoal(*input_goal));
00331 goal.reset(copy);
00332 fillGrasps(*copy);
00333 }
00334 else
00335 goal = input_goal;
00336
00337 moveit_msgs::PickupResult action_res;
00338
00339 if (goal->planning_options.plan_only || !context_->allow_trajectory_execution_)
00340 {
00341 if (!goal->planning_options.plan_only)
00342 ROS_WARN("This instance of MoveGroup is not allowed to execute trajectories but the pick goal request has plan_only set to false. Only a motion plan will be computed anyway.");
00343 executePickupCallback_PlanOnly(goal, action_res);
00344 }
00345 else
00346 executePickupCallback_PlanAndExecute(goal, action_res);
00347
00348 bool planned_trajectory_empty = action_res.trajectory_stages.empty();
00349 std::string response = getActionResultString(action_res.error_code, planned_trajectory_empty, goal->planning_options.plan_only);
00350 if (action_res.error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
00351 pickup_action_server_->setSucceeded(action_res, response);
00352 else
00353 {
00354 if (action_res.error_code.val == moveit_msgs::MoveItErrorCodes::PREEMPTED)
00355 pickup_action_server_->setPreempted(action_res, response);
00356 else
00357 pickup_action_server_->setAborted(action_res, response);
00358 }
00359
00360 setPickupState(IDLE);
00361 }
00362
00363 void move_group::MoveGroupPickPlaceAction::executePlaceCallback(const moveit_msgs::PlaceGoalConstPtr& goal)
00364 {
00365 setPlaceState(PLANNING);
00366
00367 context_->planning_scene_monitor_->updateFrameTransforms();
00368
00369 moveit_msgs::PlaceResult action_res;
00370
00371 if (goal->planning_options.plan_only || !context_->allow_trajectory_execution_)
00372 {
00373 if (!goal->planning_options.plan_only)
00374 ROS_WARN("This instance of MoveGroup is not allowed to execute trajectories but the place goal request has plan_only set to false. Only a motion plan will be computed anyway.");
00375 executePlaceCallback_PlanOnly(goal, action_res);
00376 }
00377 else
00378 executePlaceCallback_PlanAndExecute(goal, action_res);
00379
00380 bool planned_trajectory_empty = action_res.trajectory_stages.empty();
00381 std::string response = getActionResultString(action_res.error_code, planned_trajectory_empty, goal->planning_options.plan_only);
00382 if (action_res.error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
00383 place_action_server_->setSucceeded(action_res, response);
00384 else
00385 {
00386 if (action_res.error_code.val == moveit_msgs::MoveItErrorCodes::PREEMPTED)
00387 place_action_server_->setPreempted(action_res, response);
00388 else
00389 place_action_server_->setAborted(action_res, response);
00390 }
00391
00392 setPlaceState(IDLE);
00393 }
00394
00395 void move_group::MoveGroupPickPlaceAction::preemptPickupCallback()
00396 {
00397 }
00398
00399 void move_group::MoveGroupPickPlaceAction::preemptPlaceCallback()
00400 {
00401 }
00402
00403 void move_group::MoveGroupPickPlaceAction::setPickupState(MoveGroupState state)
00404 {
00405 pickup_state_ = state;
00406 pickup_feedback_.state = stateToStr(state);
00407 pickup_action_server_->publishFeedback(pickup_feedback_);
00408 }
00409
00410 void move_group::MoveGroupPickPlaceAction::setPlaceState(MoveGroupState state)
00411 {
00412 place_state_ = state;
00413 place_feedback_.state = stateToStr(state);
00414 place_action_server_->publishFeedback(place_feedback_);
00415 }
00416
00417 void move_group::MoveGroupPickPlaceAction::fillGrasps(moveit_msgs::PickupGoal& goal)
00418 {
00419 planning_scene_monitor::LockedPlanningSceneRO lscene(context_->planning_scene_monitor_);
00420
00421 if (grasp_planning_service_ && lscene->hasObjectType(goal.target_name) && !lscene->getObjectType(goal.target_name).key.empty())
00422 {
00423 manipulation_msgs::GraspPlanning::Request request;
00424 manipulation_msgs::GraspPlanning::Response response;
00425 bool valid = true;
00426
00427 collision_detection::World::ObjectConstPtr object = lscene->getWorld()->getObject(goal.target_name);
00428 if (object && !object->shape_poses_.empty())
00429 {
00430 request.arm_name = goal.group_name;
00431 request.target.reference_frame_id = lscene->getPlanningFrame();
00432
00433 household_objects_database_msgs::DatabaseModelPose dbp;
00434 dbp.pose.header.frame_id = lscene->getPlanningFrame();
00435 dbp.pose.header.stamp = ros::Time::now();
00436 tf::poseEigenToMsg(object->shape_poses_[0], dbp.pose.pose);
00437 dbp.type = lscene->getObjectType(goal.target_name);
00438 try
00439 {
00440 dbp.model_id = boost::lexical_cast<int>(dbp.type.key);
00441 ROS_DEBUG("Asking database for grasps for '%s' with model id: %d", dbp.type.key.c_str(), dbp.model_id);
00442 request.target.potential_models.push_back(dbp);
00443 }
00444 catch (boost::bad_lexical_cast &)
00445 {
00446 valid = false;
00447 ROS_ERROR("Expected an integer object id, not '%s'", dbp.type.key.c_str());
00448 }
00449 }
00450 else
00451 {
00452 valid = false;
00453 ROS_ERROR("Object has no geometry");
00454 }
00455
00456 if (valid)
00457 {
00458 ROS_DEBUG("Calling grasp planner...");
00459 if (grasp_planning_service_.call(request, response))
00460 {
00461 goal.possible_grasps.resize(response.grasps.size());
00462 for (std::size_t i = 0 ; i < response.grasps.size() ; ++i)
00463 {
00464
00465 goal.possible_grasps[i].id = response.grasps[i].id;
00466
00467 goal.possible_grasps[i].pre_grasp_posture.header = response.grasps[i].pre_grasp_posture.header;
00468 goal.possible_grasps[i].pre_grasp_posture.joint_names = response.grasps[i].pre_grasp_posture.name;
00469 goal.possible_grasps[i].pre_grasp_posture.points.resize(1);
00470 goal.possible_grasps[i].pre_grasp_posture.points[0].positions = response.grasps[i].pre_grasp_posture.position;
00471 goal.possible_grasps[i].pre_grasp_posture.points[0].velocities = response.grasps[i].pre_grasp_posture.velocity;
00472 goal.possible_grasps[i].pre_grasp_posture.points[0].effort = response.grasps[i].pre_grasp_posture.effort;
00473
00474 goal.possible_grasps[i].grasp_posture.header = response.grasps[i].grasp_posture.header;
00475 goal.possible_grasps[i].grasp_posture.joint_names = response.grasps[i].grasp_posture.name;
00476 goal.possible_grasps[i].grasp_posture.points.resize(1);
00477 goal.possible_grasps[i].grasp_posture.points[0].positions = response.grasps[i].grasp_posture.position;
00478 goal.possible_grasps[i].grasp_posture.points[0].velocities = response.grasps[i].grasp_posture.velocity;
00479 goal.possible_grasps[i].grasp_posture.points[0].effort = response.grasps[i].grasp_posture.effort;
00480
00481 goal.possible_grasps[i].grasp_pose = response.grasps[i].grasp_pose;
00482 goal.possible_grasps[i].grasp_quality = response.grasps[i].grasp_quality;
00483
00484 goal.possible_grasps[i].pre_grasp_approach.direction = response.grasps[i].approach.direction;
00485 goal.possible_grasps[i].pre_grasp_approach.desired_distance = response.grasps[i].approach.desired_distance;
00486 goal.possible_grasps[i].pre_grasp_approach.min_distance = response.grasps[i].approach.min_distance;
00487
00488
00489
00490 goal.possible_grasps[i].post_grasp_retreat.direction.vector.x = 0.0;
00491 goal.possible_grasps[i].post_grasp_retreat.direction.vector.y = 0.0;
00492 goal.possible_grasps[i].post_grasp_retreat.direction.vector.z = 1.0;
00493 goal.possible_grasps[i].post_grasp_retreat.desired_distance = 0.1;
00494 goal.possible_grasps[i].post_grasp_retreat.min_distance = 0.0;
00495 goal.possible_grasps[i].post_grasp_retreat.direction.header.frame_id = lscene->getPlanningFrame();
00496
00497 goal.possible_grasps[i].post_place_retreat.direction = response.grasps[i].retreat.direction;
00498 goal.possible_grasps[i].post_place_retreat.desired_distance = response.grasps[i].retreat.desired_distance;
00499 goal.possible_grasps[i].post_place_retreat.min_distance = response.grasps[i].retreat.min_distance;
00500
00501 goal.possible_grasps[i].max_contact_force = response.grasps[i].max_contact_force;
00502 goal.possible_grasps[i].allowed_touch_objects = response.grasps[i].allowed_touch_objects;
00503 }
00504 }
00505 }
00506 }
00507
00508 if (goal.possible_grasps.empty())
00509 {
00510 ROS_DEBUG("Using default grasp poses");
00511 goal.minimize_object_distance = true;
00512
00513
00514
00515 moveit_msgs::Grasp g;
00516 g.grasp_pose.header.frame_id = goal.target_name;
00517 g.grasp_pose.pose.position.x = -0.2;
00518 g.grasp_pose.pose.position.y = 0.0;
00519 g.grasp_pose.pose.position.z = 0.0;
00520 g.grasp_pose.pose.orientation.x = 0.0;
00521 g.grasp_pose.pose.orientation.y = 0.0;
00522 g.grasp_pose.pose.orientation.z = 0.0;
00523 g.grasp_pose.pose.orientation.w = 1.0;
00524
00525 g.pre_grasp_approach.direction.header.frame_id = lscene->getPlanningFrame();
00526 g.pre_grasp_approach.direction.vector.x = 1.0;
00527 g.pre_grasp_approach.min_distance = 0.1;
00528 g.pre_grasp_approach.desired_distance = 0.2;
00529
00530 g.post_grasp_retreat.direction.header.frame_id = lscene->getPlanningFrame();
00531 g.post_grasp_retreat.direction.vector.z = 1.0;
00532 g.post_grasp_retreat.min_distance = 0.1;
00533 g.post_grasp_retreat.desired_distance = 0.2;
00534
00535 if (lscene->getRobotModel()->hasEndEffector(goal.end_effector))
00536 {
00537 g.pre_grasp_posture.joint_names = lscene->getRobotModel()->getEndEffector(goal.end_effector)->getJointModelNames();
00538 g.pre_grasp_posture.points.resize(1);
00539 g.pre_grasp_posture.points[0].positions.resize(g.pre_grasp_posture.joint_names.size(), std::numeric_limits<double>::max());
00540
00541 g.grasp_posture.joint_names = g.pre_grasp_posture.joint_names;
00542 g.grasp_posture.points.resize(1);
00543 g.grasp_posture.points[0].positions.resize(g.grasp_posture.joint_names.size(), -std::numeric_limits<double>::max());
00544 }
00545 goal.possible_grasps.push_back(g);
00546 }
00547 }
00548
00549 #include <class_loader/class_loader.h>
00550 CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupPickPlaceAction, move_group::MoveGroupCapability)