place.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 
43 #include <tf2_eigen/tf2_eigen.h>
44 #include <ros/console.h>
45 
46 namespace pick_place
47 {
48 PlacePlan::PlacePlan(const PickPlaceConstPtr& pick_place) : PickPlacePlanBase(pick_place, "place")
49 {
50 }
51 
52 namespace
53 {
54 struct OrderPlaceLocationQuality
55 {
56  OrderPlaceLocationQuality(const std::vector<moveit_msgs::PlaceLocation>& places) : places_(places)
57  {
58  }
59 
60  bool operator()(const std::size_t a, const std::size_t b) const
61  {
62  return places_[a].quality > places_[b].quality;
63  }
64 
65  const std::vector<moveit_msgs::PlaceLocation>& places_;
66 };
67 
68 bool transformToEndEffectorGoal(const geometry_msgs::PoseStamped& goal_pose,
69  const moveit::core::AttachedBody* attached_body, geometry_msgs::PoseStamped& place_pose)
70 {
71  const EigenSTL::vector_Isometry3d& fixed_transforms = attached_body->getShapePosesInLinkFrame();
72  if (fixed_transforms.empty())
73  return false;
74 
75  Eigen::Isometry3d end_effector_transform;
76  tf2::fromMsg(goal_pose.pose, end_effector_transform);
77  end_effector_transform = end_effector_transform * fixed_transforms[0].inverse();
78  place_pose.header = goal_pose.header;
79  place_pose.pose = tf2::toMsg(end_effector_transform);
80  return true;
81 }
82 } // namespace
83 
84 bool PlacePlan::plan(const planning_scene::PlanningSceneConstPtr& planning_scene, const moveit_msgs::PlaceGoal& goal)
85 {
86  double timeout = goal.allowed_planning_time;
87  ros::WallTime endtime = ros::WallTime::now() + ros::WallDuration(timeout);
88  std::string attached_object_name = goal.attached_object_name;
89  const moveit::core::JointModelGroup* jmg = nullptr;
90  const moveit::core::JointModelGroup* eef = nullptr;
91 
92  // if the group specified is actually an end-effector, we use it as such
93  if (planning_scene->getRobotModel()->hasEndEffector(goal.group_name))
94  {
95  eef = planning_scene->getRobotModel()->getEndEffector(goal.group_name);
96  if (eef)
97  { // if we correctly found the eef, then we try to find out what the planning group is
98  const std::string& eef_parent = eef->getEndEffectorParentGroup().first;
99  if (eef_parent.empty())
100  {
101  ROS_ERROR_STREAM_NAMED("manipulation", "No parent group to plan in was identified based on end-effector '"
102  << goal.group_name
103  << "'. Please define a parent group in the SRDF.");
104  error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
105  return false;
106  }
107  else
108  jmg = planning_scene->getRobotModel()->getJointModelGroup(eef_parent);
109  }
110  }
111  else
112  {
113  // if a group name was specified, try to use it
114  jmg = goal.group_name.empty() ? nullptr : planning_scene->getRobotModel()->getJointModelGroup(goal.group_name);
115  if (jmg)
116  {
117  // we also try to find the corresponding eef
118  const std::vector<std::string>& eef_names = jmg->getAttachedEndEffectorNames();
119  if (eef_names.empty())
120  {
121  ROS_ERROR_STREAM_NAMED("manipulation",
122  "There are no end-effectors specified for group '" << goal.group_name << "'");
123  error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
124  return false;
125  }
126  else
127  // check to see if there is an end effector that has attached objects associaded, so we can complete the place
128  for (const std::string& eef_name : eef_names)
129  {
130  std::vector<const moveit::core::AttachedBody*> attached_bodies;
131  const moveit::core::JointModelGroup* eg = planning_scene->getRobotModel()->getEndEffector(eef_name);
132  if (eg)
133  {
134  // see if there are objects attached to links in the eef
135  planning_scene->getCurrentState().getAttachedBodies(attached_bodies, eg);
136 
137  // is is often possible that the objects are attached to the same link that the eef itself is attached,
138  // so we check for attached bodies there as well
139  const moveit::core::LinkModel* attached_link_model =
140  planning_scene->getRobotModel()->getLinkModel(eg->getEndEffectorParentGroup().second);
141  if (attached_link_model)
142  {
143  std::vector<const moveit::core::AttachedBody*> attached_bodies2;
144  planning_scene->getCurrentState().getAttachedBodies(attached_bodies2, attached_link_model);
145  attached_bodies.insert(attached_bodies.end(), attached_bodies2.begin(), attached_bodies2.end());
146  }
147  }
148 
149  // if this end effector has attached objects, we go on
150  if (!attached_bodies.empty())
151  {
152  // if the user specified the name of the attached object to place, we check that indeed
153  // the group contains this attachd body
154  if (!attached_object_name.empty())
155  {
156  bool found = false;
157  for (const moveit::core::AttachedBody* attached_body : attached_bodies)
158  if (attached_body->getName() == attached_object_name)
159  {
160  found = true;
161  break;
162  }
163  // if the attached body this group has is not the same as the one specified,
164  // we cannot use this eef
165  if (!found)
166  continue;
167  }
168 
169  // if we previoulsy have set the eef it means we have more options we could use, so things are ambiguous
170  if (eef)
171  {
172  ROS_ERROR_STREAM_NAMED("manipulation", "There are multiple end-effectors for group '"
173  << goal.group_name
174  << "' that are currently holding objects. It is ambiguous "
175  "which end-effector to use. Please specify it explicitly.");
176  error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
177  return false;
178  }
179  // set the end effector (this was initialized to NULL above)
180  eef = planning_scene->getRobotModel()->getEndEffector(eef_name);
181  }
182  }
183  }
184  }
185 
186  // if we know the attached object, but not the eef, we can try to identify that
187  if (!attached_object_name.empty() && !eef)
188  {
189  const moveit::core::AttachedBody* attached_body =
190  planning_scene->getCurrentState().getAttachedBody(attached_object_name);
191  if (attached_body)
192  {
193  // get the robot model link this attached body is associated to
194  const moveit::core::LinkModel* link = attached_body->getAttachedLink();
195  // check to see if there is a unique end effector containing the link
196  const std::vector<const moveit::core::JointModelGroup*>& eefs =
197  planning_scene->getRobotModel()->getEndEffectors();
198  for (const moveit::core::JointModelGroup* end_effector : eefs)
199  if (end_effector->hasLinkModel(link->getName()))
200  {
201  if (eef)
202  {
203  ROS_ERROR_STREAM_NAMED("manipulation", "There are multiple end-effectors that include the link '"
204  << link->getName() << "' which is where the body '"
205  << attached_object_name
206  << "' is attached. It is unclear which end-effector to use.");
207  error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
208  return false;
209  }
210  eef = end_effector;
211  }
212  }
213  // if the group is also unknown, but we just found out the eef
214  if (!jmg && eef)
215  {
216  const std::string& eef_parent = eef->getEndEffectorParentGroup().first;
217  if (eef_parent.empty())
218  {
219  ROS_ERROR_STREAM_NAMED("manipulation", "No parent group to plan in was identified based on end-effector '"
220  << goal.group_name
221  << "'. Please define a parent group in the SRDF.");
222  error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
223  return false;
224  }
225  else
226  jmg = planning_scene->getRobotModel()->getJointModelGroup(eef_parent);
227  }
228  }
229 
230  if (!jmg || !eef)
231  {
232  error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME;
233  return false;
234  }
235 
236  // try to infer attached body name if possible
237  int loop_count = 0;
238  while (attached_object_name.empty() && loop_count < 2)
239  {
240  // in the first try, look for objects attached to the eef, if the eef is known;
241  // otherwise, look for attached bodies in the planning group itself
242  std::vector<const moveit::core::AttachedBody*> attached_bodies;
243  planning_scene->getCurrentState().getAttachedBodies(attached_bodies, loop_count == 0 ? eef : jmg);
244 
245  loop_count++;
246  if (attached_bodies.size() > 1)
247  {
248  ROS_ERROR_NAMED("manipulation",
249  "Multiple attached bodies for group '%s' but no explicit attached object to place was specified",
250  goal.group_name.c_str());
251  error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_OBJECT_NAME;
252  return false;
253  }
254  else
255  attached_object_name = attached_bodies[0]->getName();
256  }
257 
258  const moveit::core::AttachedBody* attached_body =
259  planning_scene->getCurrentState().getAttachedBody(attached_object_name);
260  if (!attached_body)
261  {
262  ROS_ERROR_NAMED("manipulation", "There is no object to detach for place action");
263  error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_OBJECT_NAME;
264  return false;
265  }
266 
267  ros::WallTime start_time = ros::WallTime::now();
268 
269  // construct common data for possible manipulation plans
270  ManipulationPlanSharedDataPtr plan_data(new ManipulationPlanSharedData());
271  ManipulationPlanSharedDataConstPtr const_plan_data = plan_data;
272  plan_data->planning_group_ = jmg;
273  plan_data->end_effector_group_ = eef;
274  plan_data->ik_link_ = planning_scene->getRobotModel()->getLinkModel(eef->getEndEffectorParentGroup().second);
275 
276  plan_data->timeout_ = endtime;
277  plan_data->path_constraints_ = goal.path_constraints;
278  plan_data->planner_id_ = goal.planner_id;
279  plan_data->minimize_object_distance_ = false;
280  plan_data->max_goal_sampling_attempts_ = 2;
281  moveit_msgs::AttachedCollisionObject& detach_object_msg = plan_data->diff_attached_object_;
282 
283  // construct the attached object message that will change the world to what it would become after a placement
284  detach_object_msg.link_name = attached_body->getAttachedLinkName();
285  detach_object_msg.object.id = attached_object_name;
286  detach_object_msg.object.operation = moveit_msgs::CollisionObject::REMOVE;
287 
288  collision_detection::AllowedCollisionMatrixPtr approach_place_acm(
289  new collision_detection::AllowedCollisionMatrix(planning_scene->getAllowedCollisionMatrix()));
290 
291  // we are allowed to touch certain other objects with the gripper
292  approach_place_acm->setEntry(eef->getLinkModelNames(), goal.allowed_touch_objects, true);
293 
294  // we are allowed to touch the target object slightly while retreating the end effector
295  std::vector<std::string> touch_links(attached_body->getTouchLinks().begin(), attached_body->getTouchLinks().end());
296  approach_place_acm->setEntry(attached_object_name, touch_links, true);
297 
298  if (!goal.support_surface_name.empty())
299  {
300  // we are allowed to have contact between the target object and the support surface before the place
301  approach_place_acm->setEntry(goal.support_surface_name, attached_object_name, true);
302 
303  // optionally, it may be allowed to touch the support surface with the gripper
304  if (goal.allow_gripper_support_collision)
305  approach_place_acm->setEntry(goal.support_surface_name, eef->getLinkModelNames(), true);
306  }
307 
308  // configure the manipulation pipeline
309  pipeline_.reset();
310 
311  ManipulationStagePtr stage1(
312  new ReachableAndValidPoseFilter(planning_scene, approach_place_acm, pick_place_->getConstraintsSamplerManager()));
313  ManipulationStagePtr stage2(new ApproachAndTranslateStage(planning_scene, approach_place_acm));
314  ManipulationStagePtr stage3(new PlanStage(planning_scene, pick_place_->getPlanningPipeline()));
315  pipeline_.addStage(stage1).addStage(stage2).addStage(stage3);
316 
317  initialize();
318 
319  pipeline_.start();
320 
321  // order the place locations by quality
322  std::vector<std::size_t> place_locations_order(goal.place_locations.size());
323  for (std::size_t i = 0; i < goal.place_locations.size(); ++i)
324  place_locations_order[i] = i;
325  OrderPlaceLocationQuality oq(goal.place_locations);
326  // using stable_sort to preserve order of place locations with equal quality
327  std::stable_sort(place_locations_order.begin(), place_locations_order.end(), oq);
328 
329  // add possible place locations
330  for (std::size_t i = 0; i < goal.place_locations.size(); ++i)
331  {
332  ManipulationPlanPtr p(new ManipulationPlan(const_plan_data));
333  const moveit_msgs::PlaceLocation& pl = goal.place_locations[place_locations_order[i]];
334 
335  if (goal.place_eef)
336  p->goal_pose_ = pl.place_pose;
337  else
338  // The goals are specified for the attached body
339  // but we want to transform them into goals for the end-effector instead
340  if (!transformToEndEffectorGoal(pl.place_pose, attached_body, p->goal_pose_))
341  {
342  p->goal_pose_ = pl.place_pose;
343  ROS_ERROR_NAMED("manipulation", "Unable to transform the desired pose of the object to the pose of the "
344  "end-effector");
345  }
346 
347  p->approach_ = pl.pre_place_approach;
348  p->retreat_ = pl.post_place_retreat;
349  p->retreat_posture_ = pl.post_place_posture;
350  p->id_ = place_locations_order[i];
351  if (p->retreat_posture_.joint_names.empty())
352  p->retreat_posture_ = attached_body->getDetachPosture();
353  pipeline_.push(p);
354  }
355  ROS_INFO_NAMED("manipulation", "Added %d place locations", (int)goal.place_locations.size());
356 
357  // wait till we're done
358  waitForPipeline(endtime);
359 
360  pipeline_.stop();
361 
362  last_plan_time_ = (ros::WallTime::now() - start_time).toSec();
363 
364  if (!getSuccessfulManipulationPlans().empty())
365  error_code_.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
366  else
367  {
368  if (last_plan_time_ > timeout)
369  error_code_.val = moveit_msgs::MoveItErrorCodes::TIMED_OUT;
370  else
371  {
372  error_code_.val = moveit_msgs::MoveItErrorCodes::PLANNING_FAILED;
373  if (!goal.place_locations.empty())
374  {
375  ROS_WARN_NAMED("manipulation", "All supplied place locations failed. Retrying last location in verbose mode.");
376  // everything failed. we now start the pipeline again in verbose mode for one grasp
377  initialize();
378  pipeline_.setVerbose(true);
379  pipeline_.start();
380  pipeline_.reprocessLastFailure();
381  waitForPipeline(ros::WallTime::now() + ros::WallDuration(1.0));
382  pipeline_.stop();
383  pipeline_.setVerbose(false);
384  }
385  }
386  }
387  ROS_INFO_NAMED("manipulation", "Place planning completed after %lf seconds", last_plan_time_);
388 
389  return error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS;
390 }
391 
392 PlacePlanPtr PickPlace::planPlace(const planning_scene::PlanningSceneConstPtr& planning_scene,
393  const moveit_msgs::PlaceGoal& goal) const
394 {
395  PlacePlanPtr p(new PlacePlan(shared_from_this()));
396  if (moveit::core::isEmpty(goal.planning_options.planning_scene_diff))
397  p->plan(planning_scene, goal);
398  else
399  p->plan(planning_scene->diff(goal.planning_options.planning_scene_diff), goal);
400 
401  if (display_computed_motion_plans_)
402  {
403  const std::vector<pick_place::ManipulationPlanPtr>& success = p->getSuccessfulManipulationPlans();
404  if (!success.empty())
405  visualizePlan(success.back());
406  }
407 
408  if (display_grasps_)
409  {
410  const std::vector<pick_place::ManipulationPlanPtr>& success = p->getSuccessfulManipulationPlans();
411  visualizeGrasps(success);
412  const std::vector<pick_place::ManipulationPlanPtr>& failed = p->getFailedManipulationPlans();
413  visualizeGrasps(failed);
414  }
415 
416  return p;
417 }
418 } // namespace pick_place
moveit::core::LinkModel
pick_place
Definition: approach_and_translate_stage.h:43
moveit::core::AttachedBody::getDetachPosture
const trajectory_msgs::JointTrajectory & getDetachPosture() const
initialize
bool initialize(MeshCollisionTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, bool use_refit, bool refit_bottomup)
EigenSTL::vector_Isometry3d
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
pick_place::PlacePlan::PlacePlan
PlacePlan(const PickPlaceConstPtr &pick_place)
Definition: place.cpp:80
tf2_eigen.h
tf2::fromMsg
void fromMsg(const A &, B &b)
moveit::core::AttachedBody::getShapePosesInLinkFrame
const EigenSTL::vector_Isometry3d & getShapePosesInLinkFrame() const
moveit::core::AttachedBody::getTouchLinks
const std::set< std::string > & getTouchLinks() const
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
pick_place.h
plan_stage.h
moveit::core::JointModelGroup::getAttachedEndEffectorNames
const std::vector< std::string > & getAttachedEndEffectorNames() const
moveit::core::AttachedBody
console.h
collision_detection::AllowedCollisionMatrix
message_checks.h
moveit::core::isEmpty
bool isEmpty(const geometry_msgs::Pose &msg)
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
ros::WallTime::now
static WallTime now()
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
places_
const std::vector< moveit_msgs::PlaceLocation > & places_
Definition: place.cpp:97
moveit::core::AttachedBody::getAttachedLink
const LinkModel * getAttachedLink() const
ros::WallTime
moveit::core::JointModelGroup::getLinkModelNames
const std::vector< std::string > & getLinkModelNames() const
approach_and_translate_stage.h
moveit::core::AttachedBody::getAttachedLinkName
const std::string & getAttachedLinkName() const
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
moveit::core::JointModelGroup
tf2::toMsg
B toMsg(const A &a)
conversions.h
ros::WallDuration
moveit::core::LinkModel::getName
const std::string & getName() const
planning_scene
moveit::core::JointModelGroup::getEndEffectorParentGroup
const std::pair< std::string, std::string > & getEndEffectorParentGroup() const
moveit::core::AttachedBody::getName
const std::string & getName() const
reachable_valid_pose_filter.h


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