constraint_sampler_manager.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, 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 
40 #include <sstream>
41 
42 constraint_samplers::ConstraintSamplerPtr constraint_samplers::ConstraintSamplerManager::selectSampler(
43  const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name,
44  const moveit_msgs::Constraints& constr) const
45 {
46  for (std::size_t i = 0; i < sampler_alloc_.size(); ++i)
47  if (sampler_alloc_[i]->canService(scene, group_name, constr))
48  return sampler_alloc_[i]->alloc(scene, group_name, constr);
49 
50  // if no default sampler was used, try a default one
51  return selectDefaultSampler(scene, group_name, constr);
52 }
53 
55  const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name,
56  const moveit_msgs::Constraints& constr)
57 {
58  const robot_model::JointModelGroup* jmg = scene->getRobotModel()->getJointModelGroup(group_name);
59  if (!jmg)
60  return constraint_samplers::ConstraintSamplerPtr();
61  std::stringstream ss;
62  ss << constr;
63  ROS_DEBUG_NAMED("constraint_samplers",
64  "Attempting to construct constrained state sampler for group '%s', using constraints:\n%s.\n",
65  jmg->getName().c_str(), ss.str().c_str());
66 
67  ConstraintSamplerPtr joint_sampler; // location to put chosen joint sampler if needed
68  // if there are joint constraints, we could possibly get a sampler from those
69  if (!constr.joint_constraints.empty())
70  {
71  ROS_DEBUG_NAMED("constraint_samplers", "There are joint constraints specified. "
72  "Attempting to construct a JointConstraintSampler for group '%s'",
73  jmg->getName().c_str());
74 
75  std::map<std::string, bool> joint_coverage;
76  for (std::size_t i = 0; i < jmg->getVariableNames().size(); ++i)
77  joint_coverage[jmg->getVariableNames()[i]] = false;
78 
79  // construct the constraints
80  std::vector<kinematic_constraints::JointConstraint> jc;
81  for (std::size_t i = 0; i < constr.joint_constraints.size(); ++i)
82  {
83  kinematic_constraints::JointConstraint j(scene->getRobotModel());
84  if (j.configure(constr.joint_constraints[i]))
85  {
86  if (joint_coverage.find(j.getJointVariableName()) != joint_coverage.end())
87  {
88  joint_coverage[j.getJointVariableName()] = true;
89  jc.push_back(j);
90  }
91  }
92  }
93 
94  // check if every joint is covered (constrained) by just joint samplers
95  bool full_coverage = true;
96  for (std::map<std::string, bool>::iterator it = joint_coverage.begin(); it != joint_coverage.end(); ++it)
97  if (!it->second)
98  {
99  full_coverage = false;
100  break;
101  }
102 
103  // if we have constrained every joint, then we just use a sampler using these constraints
104  if (full_coverage)
105  {
106  JointConstraintSamplerPtr sampler(new JointConstraintSampler(scene, jmg->getName()));
107  if (sampler->configure(jc))
108  {
109  ROS_DEBUG_NAMED("constraint_samplers", "Allocated a sampler satisfying joint constraints for group '%s'",
110  jmg->getName().c_str());
111  return sampler;
112  }
113  }
114  else
115  // if a smaller set of joints has been specified, keep the constraint sampler around, but use it only if no IK
116  // sampler has been specified.
117  if (!jc.empty())
118  {
119  JointConstraintSamplerPtr sampler(new JointConstraintSampler(scene, jmg->getName()));
120  if (sampler->configure(jc))
121  {
122  ROS_DEBUG_NAMED("constraint_samplers",
123  "Temporary sampler satisfying joint constraints for group '%s' allocated. "
124  "Looking for different types of constraints before returning though.",
125  jmg->getName().c_str());
126  joint_sampler = sampler;
127  }
128  }
129  }
130 
131  std::vector<ConstraintSamplerPtr> samplers;
132  if (joint_sampler) // Start making a union of constraint samplers
133  samplers.push_back(joint_sampler);
134 
135  // read the ik allocators, if any
136  const robot_model::JointModelGroup::KinematicsSolver& ik_alloc = jmg->getGroupKinematics().first;
137  const robot_model::JointModelGroup::KinematicsSolverMap& ik_subgroup_alloc = jmg->getGroupKinematics().second;
138 
139  // if we have a means of computing complete states for the group using IK, then we try to see if any IK constraints
140  // should be used
141  if (ik_alloc)
142  {
143  ROS_DEBUG_NAMED("constraint_samplers", "There is an IK allocator for '%s'. "
144  "Checking for corresponding position and/or orientation constraints",
145  jmg->getName().c_str());
146 
147  // keep track of which links we constrained
148  std::map<std::string, IKConstraintSamplerPtr> usedL;
149 
150  // if we have position and/or orientation constraints on links that we can perform IK for,
151  // we will use a sampleable goal region that employs IK to sample goals;
152  // if there are multiple constraints for the same link, we keep the one with the smallest
153  // volume for sampling
154  for (std::size_t p = 0; p < constr.position_constraints.size(); ++p)
155  for (std::size_t o = 0; o < constr.orientation_constraints.size(); ++o)
156  if (constr.position_constraints[p].link_name == constr.orientation_constraints[o].link_name)
157  {
158  kinematic_constraints::PositionConstraintPtr pc(
159  new kinematic_constraints::PositionConstraint(scene->getRobotModel()));
160  kinematic_constraints::OrientationConstraintPtr oc(
161  new kinematic_constraints::OrientationConstraint(scene->getRobotModel()));
162  if (pc->configure(constr.position_constraints[p], scene->getTransforms()) &&
163  oc->configure(constr.orientation_constraints[o], scene->getTransforms()))
164  {
165  IKConstraintSamplerPtr iks(new IKConstraintSampler(scene, jmg->getName()));
166  if (iks->configure(IKSamplingPose(pc, oc)))
167  {
168  bool use = true;
169  // Check if there already is a constraint on this link
170  if (usedL.find(constr.position_constraints[p].link_name) != usedL.end())
171  // If there is, check if the previous one has a smaller volume for sampling
172  if (usedL[constr.position_constraints[p].link_name]->getSamplingVolume() < iks->getSamplingVolume())
173  use = false; // only use new constraint if it has a smaller sampling volume
174  if (use)
175  {
176  // assign the link to a new constraint sampler
177  usedL[constr.position_constraints[p].link_name] = iks;
178  ROS_DEBUG_NAMED("constraint_samplers", "Allocated an IK-based sampler for group '%s' "
179  "satisfying position and orientation constraints on link '%s'",
180  jmg->getName().c_str(), constr.position_constraints[p].link_name.c_str());
181  }
182  }
183  }
184  }
185 
186  // keep track of links constrained with a full pose
187  std::map<std::string, IKConstraintSamplerPtr> usedL_fullPose = usedL;
188 
189  for (std::size_t p = 0; p < constr.position_constraints.size(); ++p)
190  {
191  // if we are constraining this link with a full pose, we do not attempt to constrain it with a position constraint
192  // only
193  if (usedL_fullPose.find(constr.position_constraints[p].link_name) != usedL_fullPose.end())
194  continue;
195 
196  kinematic_constraints::PositionConstraintPtr pc(
197  new kinematic_constraints::PositionConstraint(scene->getRobotModel()));
198  if (pc->configure(constr.position_constraints[p], scene->getTransforms()))
199  {
200  IKConstraintSamplerPtr iks(new IKConstraintSampler(scene, jmg->getName()));
201  if (iks->configure(IKSamplingPose(pc)))
202  {
203  bool use = true;
204  if (usedL.find(constr.position_constraints[p].link_name) != usedL.end())
205  if (usedL[constr.position_constraints[p].link_name]->getSamplingVolume() < iks->getSamplingVolume())
206  use = false;
207  if (use)
208  {
209  usedL[constr.position_constraints[p].link_name] = iks;
210  ROS_DEBUG_NAMED("constraint_samplers", "Allocated an IK-based sampler for group '%s' "
211  "satisfying position constraints on link '%s'",
212  jmg->getName().c_str(), constr.position_constraints[p].link_name.c_str());
213  }
214  }
215  }
216  }
217 
218  for (std::size_t o = 0; o < constr.orientation_constraints.size(); ++o)
219  {
220  // if we are constraining this link with a full pose, we do not attempt to constrain it with an orientation
221  // constraint only
222  if (usedL_fullPose.find(constr.orientation_constraints[o].link_name) != usedL_fullPose.end())
223  continue;
224 
225  kinematic_constraints::OrientationConstraintPtr oc(
226  new kinematic_constraints::OrientationConstraint(scene->getRobotModel()));
227  if (oc->configure(constr.orientation_constraints[o], scene->getTransforms()))
228  {
229  IKConstraintSamplerPtr iks(new IKConstraintSampler(scene, jmg->getName()));
230  if (iks->configure(IKSamplingPose(oc)))
231  {
232  bool use = true;
233  if (usedL.find(constr.orientation_constraints[o].link_name) != usedL.end())
234  if (usedL[constr.orientation_constraints[o].link_name]->getSamplingVolume() < iks->getSamplingVolume())
235  use = false;
236  if (use)
237  {
238  usedL[constr.orientation_constraints[o].link_name] = iks;
239  ROS_DEBUG_NAMED("constraint_samplers", "Allocated an IK-based sampler for group '%s' "
240  "satisfying orientation constraints on link '%s'",
241  jmg->getName().c_str(), constr.orientation_constraints[o].link_name.c_str());
242  }
243  }
244  }
245  }
246 
247  if (usedL.size() == 1)
248  {
249  if (samplers.empty())
250  return usedL.begin()->second;
251  else
252  {
253  samplers.push_back(usedL.begin()->second);
254  return ConstraintSamplerPtr(new UnionConstraintSampler(scene, jmg->getName(), samplers));
255  }
256  }
257  else if (usedL.size() > 1)
258  {
259  ROS_DEBUG_NAMED("constraint_samplers",
260  "Too many IK-based samplers for group '%s'. Keeping the one with minimal sampling volume",
261  jmg->getName().c_str());
262  // find the sampler with the smallest sampling volume; delete the rest
263  IKConstraintSamplerPtr iks = usedL.begin()->second;
264  double msv = iks->getSamplingVolume();
265  for (std::map<std::string, IKConstraintSamplerPtr>::const_iterator it = ++usedL.begin(); it != usedL.end(); ++it)
266  {
267  double v = it->second->getSamplingVolume();
268  if (v < msv)
269  {
270  iks = it->second;
271  msv = v;
272  }
273  }
274  if (samplers.empty())
275  {
276  return iks;
277  }
278  else
279  {
280  samplers.push_back(iks);
281  return ConstraintSamplerPtr(new UnionConstraintSampler(scene, jmg->getName(), samplers));
282  }
283  }
284  }
285 
286  // if we got to this point, we have not decided on a sampler.
287  // we now check to see if we can use samplers from subgroups
288  if (!ik_subgroup_alloc.empty())
289  {
290  ROS_DEBUG_NAMED("constraint_samplers", "There are IK allocators for subgroups of group '%s'. "
291  "Checking for corresponding position and/or orientation constraints",
292  jmg->getName().c_str());
293 
294  bool some_sampler_valid = false;
295 
296  std::set<std::size_t> usedP, usedO;
297  for (robot_model::JointModelGroup::KinematicsSolverMap::const_iterator it = ik_subgroup_alloc.begin();
298  it != ik_subgroup_alloc.end(); ++it)
299  {
300  // construct a sub-set of constraints that operate on the sub-group for which we have an IK allocator
301  moveit_msgs::Constraints sub_constr;
302  for (std::size_t p = 0; p < constr.position_constraints.size(); ++p)
303  if (it->first->hasLinkModel(constr.position_constraints[p].link_name))
304  if (usedP.find(p) == usedP.end())
305  {
306  sub_constr.position_constraints.push_back(constr.position_constraints[p]);
307  usedP.insert(p);
308  }
309 
310  for (std::size_t o = 0; o < constr.orientation_constraints.size(); ++o)
311  if (it->first->hasLinkModel(constr.orientation_constraints[o].link_name))
312  if (usedO.find(o) == usedO.end())
313  {
314  sub_constr.orientation_constraints.push_back(constr.orientation_constraints[o]);
315  usedO.insert(o);
316  }
317 
318  // if some matching constraints were found, construct the allocator
319  if (!sub_constr.orientation_constraints.empty() || !sub_constr.position_constraints.empty())
320  {
321  ROS_DEBUG_NAMED("constraint_samplers", "Attempting to construct a sampler for the '%s' subgroup of '%s'",
322  it->first->getName().c_str(), jmg->getName().c_str());
323  ConstraintSamplerPtr cs = selectDefaultSampler(scene, it->first->getName(), sub_constr);
324  if (cs)
325  {
326  ROS_DEBUG_NAMED("constraint_samplers", "Constructed a sampler for the joints corresponding to group '%s', "
327  "but part of group '%s'",
328  it->first->getName().c_str(), jmg->getName().c_str());
329  some_sampler_valid = true;
330  samplers.push_back(cs);
331  }
332  }
333  }
334  if (some_sampler_valid)
335  {
336  ROS_DEBUG_NAMED("constraint_samplers", "Constructing sampler for group '%s' as a union of %zu samplers",
337  jmg->getName().c_str(), samplers.size());
338  return ConstraintSamplerPtr(new UnionConstraintSampler(scene, jmg->getName(), samplers));
339  }
340  }
341 
342  // if we've gotten here, just return joint sampler
343  if (joint_sampler)
344  {
345  ROS_DEBUG_NAMED("constraint_samplers", "Allocated a sampler satisfying joint constraints for group '%s'",
346  jmg->getName().c_str());
347  return joint_sampler;
348  }
349 
350  ROS_DEBUG_NAMED("constraint_samplers", "No constraints sampler allocated for group '%s'", jmg->getName().c_str());
351 
352  return ConstraintSamplerPtr();
353 }
A structure for potentially holding a position constraint and an orientation constraint for use durin...
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
Class for constraints on the orientation of a link.
std::vector< ConstraintSamplerAllocatorPtr > sampler_alloc_
Holds the constraint sampler allocators, which will be tested in order.
const std::string & getName() const
Get the name of the joint group.
Class for handling single DOF joint constraints.
This class exists as a union of constraint samplers. It contains a vector of constraint samplers...
JointConstraintSampler is a class that allows the sampling of joints in a particular group of the rob...
#define ROS_DEBUG_NAMED(name,...)
const std::pair< KinematicsSolver, KinematicsSolverMap > & getGroupKinematics() const
A class that allows the sampling of IK constraints.
std::map< const JointModelGroup *, KinematicsSolver > KinematicsSolverMap
Map from group instances to allocator functions & bijections.
Class for constraints on the XYZ position of a link.
ConstraintSamplerPtr selectSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::Constraints &constr) const
Selects among the potential sampler allocators.
static ConstraintSamplerPtr selectDefaultSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const moveit_msgs::Constraints &constr)
Default logic to select a ConstraintSampler given a constraints message.


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 18 2018 02:48:31