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