pick.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
42 #include <ros/console.h>
43 
44 namespace pick_place
45 {
46 PickPlan::PickPlan(const PickPlaceConstPtr& pick_place) : PickPlacePlanBase(pick_place, "pick")
47 {
48 }
49 
50 namespace
51 {
52 struct OrderGraspQuality
53 {
54  OrderGraspQuality(const std::vector<moveit_msgs::Grasp>& grasps) : grasps_(grasps)
55  {
56  }
57 
58  bool operator()(const std::size_t a, const std::size_t b) const
59  {
60  return grasps_[a].grasp_quality > grasps_[b].grasp_quality;
61  }
62 
63  const std::vector<moveit_msgs::Grasp>& grasps_;
64 };
65 } // namespace
66 
67 bool PickPlan::plan(const planning_scene::PlanningSceneConstPtr& planning_scene, const moveit_msgs::PickupGoal& goal)
68 {
69  double timeout = goal.allowed_planning_time;
70  ros::WallTime endtime = ros::WallTime::now() + ros::WallDuration(timeout);
71 
72  std::string planning_group = goal.group_name;
73  std::string end_effector = goal.end_effector;
74  if (end_effector.empty() && !planning_group.empty())
75  {
76  const moveit::core::JointModelGroup* jmg = planning_scene->getRobotModel()->getJointModelGroup(planning_group);
77  if (!jmg)
78  {
79  error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
80  return false;
81  }
82  const std::vector<std::string>& eefs = jmg->getAttachedEndEffectorNames();
83  if (!eefs.empty())
84  {
85  end_effector = eefs.front();
86  if (eefs.size() > 1)
87  ROS_WARN_STREAM_NAMED("manipulation", "Choice of end-effector for group '"
88  << planning_group << "' is ambiguous. Assuming '" << end_effector
89  << "'");
90  }
91  }
92  else if (!end_effector.empty() && planning_group.empty())
93  {
94  const moveit::core::JointModelGroup* jmg = planning_scene->getRobotModel()->getEndEffector(end_effector);
95  if (!jmg)
96  {
97  error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
98  return false;
99  }
100  planning_group = jmg->getEndEffectorParentGroup().first;
101  if (planning_group.empty())
102  {
103  ROS_ERROR_STREAM_NAMED("manipulation", "No parent group to plan in was identified based on end-effector '"
104  << end_effector << "'. Please define a parent group in the SRDF.");
105  error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
106  return false;
107  }
108  else
109  ROS_INFO_STREAM_NAMED("manipulation", "Assuming the planning group for end effector '" << end_effector << "' is '"
110  << planning_group << "'");
111  }
112  const moveit::core::JointModelGroup* eef =
113  end_effector.empty() ? nullptr : planning_scene->getRobotModel()->getEndEffector(end_effector);
114  if (!eef)
115  {
116  ROS_ERROR_NAMED("manipulation", "No end-effector specified for pick action");
117  error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
118  return false;
119  }
120  const std::string& ik_link = eef->getEndEffectorParentGroup().second;
121 
122  ros::WallTime start_time = ros::WallTime::now();
123 
124  // construct common data for possible manipulation plans
125  ManipulationPlanSharedDataPtr plan_data(new ManipulationPlanSharedData());
126  ManipulationPlanSharedDataConstPtr const_plan_data = plan_data;
127  plan_data->planning_group_ = planning_scene->getRobotModel()->getJointModelGroup(planning_group);
128  plan_data->end_effector_group_ = eef;
129  plan_data->ik_link_ = planning_scene->getRobotModel()->getLinkModel(ik_link);
130  plan_data->timeout_ = endtime;
131  plan_data->path_constraints_ = goal.path_constraints;
132  plan_data->planner_id_ = goal.planner_id;
133  plan_data->minimize_object_distance_ = goal.minimize_object_distance;
134  plan_data->max_goal_sampling_attempts_ = 2;
135  moveit_msgs::AttachedCollisionObject& attach_object_msg = plan_data->diff_attached_object_;
136 
137  // construct the attached object message that will change the world to what it would become after a pick
138  attach_object_msg.link_name = ik_link;
139  attach_object_msg.object.id = goal.target_name;
140  attach_object_msg.object.operation = moveit_msgs::CollisionObject::ADD;
141  attach_object_msg.touch_links =
142  goal.attached_object_touch_links.empty() ? eef->getLinkModelNames() : goal.attached_object_touch_links;
143  collision_detection::AllowedCollisionMatrixPtr approach_grasp_acm(
144  new collision_detection::AllowedCollisionMatrix(planning_scene->getAllowedCollisionMatrix()));
145 
146  // we are allowed to touch the target object
147  approach_grasp_acm->setEntry(goal.target_name, attach_object_msg.touch_links, true);
148  // we are allowed to touch certain other objects with the gripper
149  approach_grasp_acm->setEntry(eef->getLinkModelNames(), goal.allowed_touch_objects, true);
150  if (!goal.support_surface_name.empty())
151  {
152  // we are allowed to have contact between the target object and the support surface before the grasp
153  approach_grasp_acm->setEntry(goal.support_surface_name, goal.target_name, true);
154 
155  // optionally, it may be allowed to touch the support surface with the gripper
156  if (goal.allow_gripper_support_collision)
157  approach_grasp_acm->setEntry(goal.support_surface_name, eef->getLinkModelNames(), true);
158  }
159 
160  // configure the manipulation pipeline
161  pipeline_.reset();
162  ManipulationStagePtr stage1(
163  new ReachableAndValidPoseFilter(planning_scene, approach_grasp_acm, pick_place_->getConstraintsSamplerManager()));
164  ManipulationStagePtr stage2(new ApproachAndTranslateStage(planning_scene, approach_grasp_acm));
165  ManipulationStagePtr stage3(new PlanStage(planning_scene, pick_place_->getPlanningPipeline()));
166  pipeline_.addStage(stage1).addStage(stage2).addStage(stage3);
167 
168  initialize();
169  pipeline_.start();
170 
171  // order the grasps by quality
172  std::vector<std::size_t> grasp_order(goal.possible_grasps.size());
173  for (std::size_t i = 0; i < goal.possible_grasps.size(); ++i)
174  grasp_order[i] = i;
175  OrderGraspQuality oq(goal.possible_grasps);
176  // using stable_sort to preserve order of grasps with equal quality
177  std::stable_sort(grasp_order.begin(), grasp_order.end(), oq);
178 
179  // feed the available grasps to the stages we set up
180  for (std::size_t i = 0; i < goal.possible_grasps.size(); ++i)
181  {
182  ManipulationPlanPtr p(new ManipulationPlan(const_plan_data));
183  const moveit_msgs::Grasp& g = goal.possible_grasps[grasp_order[i]];
184  p->approach_ = g.pre_grasp_approach;
185  p->retreat_ = g.post_grasp_retreat;
186  p->goal_pose_ = g.grasp_pose;
187  p->id_ = grasp_order[i];
188  // if no frame of reference was specified, assume the transform to be in the reference frame of the object
189  if (p->goal_pose_.header.frame_id.empty())
190  p->goal_pose_.header.frame_id = goal.target_name;
191  p->approach_posture_ = g.pre_grasp_posture;
192  p->retreat_posture_ = g.grasp_posture;
193  pipeline_.push(p);
194  }
195 
196  // wait till we're done
197  waitForPipeline(endtime);
198  pipeline_.stop();
199 
200  last_plan_time_ = (ros::WallTime::now() - start_time).toSec();
201 
202  if (!getSuccessfulManipulationPlans().empty())
203  error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
204  else
205  {
206  if (last_plan_time_ > timeout)
207  error_code_.val = moveit_msgs::MoveItErrorCodes::TIMED_OUT;
208  else
209  {
210  error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
211  if (!goal.possible_grasps.empty())
212  {
213  ROS_WARN_NAMED("manipulation", "All supplied grasps failed. Retrying last grasp in verbose mode.");
214  // everything failed. we now start the pipeline again in verbose mode for one grasp
215  initialize();
216  pipeline_.setVerbose(true);
217  pipeline_.start();
220  pipeline_.stop();
221  pipeline_.setVerbose(false);
222  }
223  }
224  }
225  ROS_INFO_NAMED("manipulation", "Pickup planning completed after %lf seconds", last_plan_time_);
226 
227  return error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS;
228 }
229 
230 PickPlanPtr PickPlace::planPick(const planning_scene::PlanningSceneConstPtr& planning_scene,
231  const moveit_msgs::PickupGoal& goal) const
232 {
233  PickPlanPtr p(new PickPlan(shared_from_this()));
234 
235  if (moveit::core::isEmpty(goal.planning_options.planning_scene_diff))
236  p->plan(planning_scene, goal);
237  else
238  p->plan(planning_scene->diff(goal.planning_options.planning_scene_diff), goal);
239 
240  if (display_computed_motion_plans_)
241  {
242  const std::vector<pick_place::ManipulationPlanPtr>& success = p->getSuccessfulManipulationPlans();
243  if (!success.empty())
244  visualizePlan(success.back());
245  }
246 
247  if (display_grasps_)
248  {
249  const std::vector<pick_place::ManipulationPlanPtr>& success = p->getSuccessfulManipulationPlans();
250  visualizeGrasps(success);
251  const std::vector<pick_place::ManipulationPlanPtr>& failed = p->getFailedManipulationPlans();
252  visualizeGrasps(failed);
253  }
254 
255  return p;
256 }
257 } // namespace pick_place
pick_place::PickPlacePlanBase::error_code_
moveit_msgs::MoveItErrorCodes error_code_
Definition: pick_place.h:124
pick_place::ManipulationPipeline::reset
void reset()
Definition: manipulation_pipeline.cpp:114
pick_place
Definition: approach_and_translate_stage.h:43
pick_place::PickPlan::plan
bool plan(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PickupGoal &goal)
Definition: pick.cpp:99
pick_place::PickPlacePlanBase::last_plan_time_
double last_plan_time_
Definition: pick_place.h:119
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
pick_place::PickPlacePlanBase::initialize
void initialize()
Definition: pick_place.cpp:109
pick_place.h
plan_stage.h
pick_place::ManipulationPipeline::stop
void stop()
Definition: manipulation_pipeline.cpp:160
moveit::core::JointModelGroup::getAttachedEndEffectorNames
const std::vector< std::string > & getAttachedEndEffectorNames() const
pick_place::PickPlacePlanBase::pipeline_
ManipulationPipeline pipeline_
Definition: pick_place.h:117
console.h
collision_detection::AllowedCollisionMatrix
message_checks.h
moveit::core::isEmpty
bool isEmpty(const geometry_msgs::Pose &msg)
pick_place::PickPlan::PickPlan
PickPlan(const PickPlaceConstPtr &pick_place)
Definition: pick.cpp:78
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
pick_place::ManipulationPipeline::push
void push(const ManipulationPlanPtr &grasp)
Definition: manipulation_pipeline.cpp:240
ros::WallTime::now
static WallTime now()
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
pick_place::ManipulationPipeline::setVerbose
void setVerbose(bool flag)
Definition: manipulation_pipeline.cpp:120
ros::WallTime
ROS_WARN_STREAM_NAMED
#define ROS_WARN_STREAM_NAMED(name, args)
pick_place::ManipulationPipeline::start
void start()
Definition: manipulation_pipeline.cpp:141
moveit::core::JointModelGroup::getLinkModelNames
const std::vector< std::string > & getLinkModelNames() const
approach_and_translate_stage.h
grasps_
const std::vector< moveit_msgs::Grasp > & grasps_
Definition: pick.cpp:95
pick_place::PickPlacePlanBase::getSuccessfulManipulationPlans
const std::vector< ManipulationPlanPtr > & getSuccessfulManipulationPlans() const
Definition: pick_place.h:91
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
moveit::core::JointModelGroup
pick_place::ManipulationPipeline::reprocessLastFailure
void reprocessLastFailure()
Definition: manipulation_pipeline.cpp:249
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
ros::WallDuration
planning_scene
moveit::core::JointModelGroup::getEndEffectorParentGroup
const std::pair< std::string, std::string > & getEndEffectorParentGroup() const
pick_place::PickPlacePlanBase::waitForPipeline
void waitForPipeline(const ros::WallTime &endtime)
Definition: pick_place.cpp:115
pick_place::PickPlacePlanBase::pick_place_
PickPlaceConstPtr pick_place_
Definition: pick_place.h:116
reachable_valid_pose_filter.h
pick_place::ManipulationPipeline::addStage
ManipulationPipeline & addStage(const ManipulationStagePtr &next)
Definition: manipulation_pipeline.cpp:85


manipulation
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Fri May 3 2024 02:29:51