42 constraint_samplers::ConstraintSamplerPtr
44 const std::string& group_name,
45 const moveit_msgs::Constraints& constr)
const
47 for (
const ConstraintSamplerAllocatorPtr& sampler :
sampler_alloc_)
48 if (sampler->canService(scene, group_name, constr))
49 return sampler->alloc(scene, group_name, constr);
55 constraint_samplers::ConstraintSamplerPtr
57 const std::string& group_name,
58 const moveit_msgs::Constraints& constr)
62 return constraint_samplers::ConstraintSamplerPtr();
66 "Attempting to construct constrained state sampler for group '%s', using constraints:\n%s.\n",
67 jmg->
getName().c_str(), ss.str().c_str());
69 ConstraintSamplerPtr joint_sampler;
71 if (!constr.joint_constraints.empty())
74 "There are joint constraints specified. "
75 "Attempting to construct a JointConstraintSampler for group '%s'",
78 std::map<std::string, bool> joint_coverage;
80 joint_coverage[joint] =
false;
83 std::vector<kinematic_constraints::JointConstraint> jc;
84 for (
const moveit_msgs::JointConstraint& joint_constraint : constr.joint_constraints)
98 bool full_coverage =
true;
99 for (
const std::pair<const std::string, bool>& it : joint_coverage)
102 full_coverage =
false;
110 if (sampler->configure(jc))
112 ROS_DEBUG_NAMED(
"constraint_samplers",
"Allocated a sampler satisfying joint constraints for group '%s'",
123 if (sampler->configure(jc))
126 "Temporary sampler satisfying joint constraints for group '%s' allocated. "
127 "Looking for different types of constraints before returning though.",
129 joint_sampler = sampler;
134 std::vector<ConstraintSamplerPtr> samplers;
136 samplers.push_back(joint_sampler);
147 "There is an IK allocator for '%s'. "
148 "Checking for corresponding position and/or orientation constraints",
152 std::map<std::string, IKConstraintSamplerPtr> used_l;
158 for (std::size_t p = 0; p < constr.position_constraints.size(); ++p)
159 for (std::size_t o = 0; o < constr.orientation_constraints.size(); ++o)
160 if (constr.position_constraints[p].link_name == constr.orientation_constraints[o].link_name)
162 kinematic_constraints::PositionConstraintPtr pc(
164 kinematic_constraints::OrientationConstraintPtr oc(
166 if (pc->configure(constr.position_constraints[p], scene->getTransforms()) &&
167 oc->configure(constr.orientation_constraints[o], scene->getTransforms()))
174 if (used_l.find(constr.position_constraints[p].link_name) != used_l.end())
176 if (used_l[constr.position_constraints[p].link_name]->getSamplingVolume() < iks->getSamplingVolume())
181 used_l[constr.position_constraints[p].link_name] = iks;
183 "Allocated an IK-based sampler for group '%s' "
184 "satisfying position and orientation constraints on link '%s'",
185 jmg->
getName().c_str(), constr.position_constraints[p].link_name.c_str());
192 std::map<std::string, IKConstraintSamplerPtr> used_l_full_pose = used_l;
194 for (
const moveit_msgs::PositionConstraint& position_constraint : constr.position_constraints)
198 if (used_l_full_pose.find(position_constraint.link_name) != used_l_full_pose.end())
201 kinematic_constraints::PositionConstraintPtr pc(
203 if (pc->configure(position_constraint, scene->getTransforms()))
209 if (used_l.find(position_constraint.link_name) != used_l.end())
210 if (used_l[position_constraint.link_name]->getSamplingVolume() < iks->getSamplingVolume())
214 used_l[position_constraint.link_name] = iks;
216 "Allocated an IK-based sampler for group '%s' "
217 "satisfying position constraints on link '%s'",
218 jmg->
getName().c_str(), position_constraint.link_name.c_str());
224 for (
const moveit_msgs::OrientationConstraint& orientation_constraint : constr.orientation_constraints)
228 if (used_l_full_pose.find(orientation_constraint.link_name) != used_l_full_pose.end())
231 kinematic_constraints::OrientationConstraintPtr oc(
233 if (oc->configure(orientation_constraint, scene->getTransforms()))
239 if (used_l.find(orientation_constraint.link_name) != used_l.end())
240 if (used_l[orientation_constraint.link_name]->getSamplingVolume() < iks->getSamplingVolume())
244 used_l[orientation_constraint.link_name] = iks;
246 "Allocated an IK-based sampler for group '%s' "
247 "satisfying orientation constraints on link '%s'",
248 jmg->
getName().c_str(), orientation_constraint.link_name.c_str());
254 if (used_l.size() == 1)
256 if (samplers.empty())
257 return used_l.begin()->second;
260 samplers.push_back(used_l.begin()->second);
264 else if (used_l.size() > 1)
267 "Too many IK-based samplers for group '%s'. Keeping the one with minimal sampling volume",
270 IKConstraintSamplerPtr iks = used_l.begin()->second;
271 double msv = iks->getSamplingVolume();
272 for (std::map<std::string, IKConstraintSamplerPtr>::const_iterator it = ++used_l.begin(); it != used_l.end(); ++it)
274 double v = it->second->getSamplingVolume();
281 if (samplers.empty())
287 samplers.push_back(iks);
295 if (!ik_subgroup_alloc.empty())
298 "There are IK allocators for subgroups of group '%s'. "
299 "Checking for corresponding position and/or orientation constraints",
302 bool some_sampler_valid =
false;
304 std::set<std::size_t> used_p, used_o;
305 for (moveit::core::JointModelGroup::KinematicsSolverMap::const_iterator it = ik_subgroup_alloc.begin();
306 it != ik_subgroup_alloc.end(); ++it)
309 moveit_msgs::Constraints sub_constr;
310 for (std::size_t p = 0; p < constr.position_constraints.size(); ++p)
311 if (it->first->hasLinkModel(constr.position_constraints[p].link_name))
312 if (used_p.find(p) == used_p.end())
314 sub_constr.position_constraints.push_back(constr.position_constraints[p]);
318 for (std::size_t o = 0; o < constr.orientation_constraints.size(); ++o)
319 if (it->first->hasLinkModel(constr.orientation_constraints[o].link_name))
320 if (used_o.find(o) == used_o.end())
322 sub_constr.orientation_constraints.push_back(constr.orientation_constraints[o]);
327 if (!sub_constr.orientation_constraints.empty() || !sub_constr.position_constraints.empty())
329 ROS_DEBUG_NAMED(
"constraint_samplers",
"Attempting to construct a sampler for the '%s' subgroup of '%s'",
330 it->first->getName().c_str(), jmg->
getName().c_str());
331 ConstraintSamplerPtr cs = selectDefaultSampler(scene, it->first->getName(), sub_constr);
335 "Constructed a sampler for the joints corresponding to group '%s', "
336 "but part of group '%s'",
337 it->first->getName().c_str(), jmg->
getName().c_str());
338 some_sampler_valid =
true;
339 samplers.push_back(cs);
343 if (some_sampler_valid)
345 ROS_DEBUG_NAMED(
"constraint_samplers",
"Constructing sampler for group '%s' as a union of %zu samplers",
346 jmg->
getName().c_str(), samplers.size());
354 ROS_DEBUG_NAMED(
"constraint_samplers",
"Allocated a sampler satisfying joint constraints for group '%s'",
356 return joint_sampler;
359 ROS_DEBUG_NAMED(
"constraint_samplers",
"No constraints sampler allocated for group '%s'", jmg->
getName().c_str());
361 return ConstraintSamplerPtr();