40 #include <rclcpp/logger.hpp>
41 #include <rclcpp/logging.hpp>
46 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_constraint_samplers.constraint_sampler_manager");
49 const std::string& group_name,
50 const moveit_msgs::msg::Constraints& constr)
const
52 for (
const ConstraintSamplerAllocatorPtr& sampler : sampler_alloc_)
53 if (sampler->canService(
scene, group_name, constr))
54 return sampler->alloc(
scene, group_name, constr);
61 const std::string& group_name,
62 const moveit_msgs::msg::Constraints& constr)
66 return ConstraintSamplerPtr();
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());
72 ConstraintSamplerPtr joint_sampler;
74 if (!constr.joint_constraints.empty())
77 "There are joint constraints specified. "
78 "Attempting to construct a JointConstraintSampler for group '%s'",
81 std::map<std::string, bool> joint_coverage;
83 joint_coverage[joint] =
false;
86 std::vector<kinematic_constraints::JointConstraint> jc;
87 for (
const moveit_msgs::msg::JointConstraint& joint_constraint : constr.joint_constraints)
101 bool full_coverage =
true;
102 for (
const std::pair<const std::string, bool>& it : joint_coverage)
105 full_coverage =
false;
112 JointConstraintSamplerPtr sampler = std::make_shared<JointConstraintSampler>(
scene, jmg->
getName());
113 if (sampler->configure(jc))
115 RCLCPP_DEBUG(LOGGER,
"Allocated a sampler satisfying joint constraints for group '%s'", jmg->
getName().c_str());
124 JointConstraintSamplerPtr sampler = std::make_shared<JointConstraintSampler>(
scene, jmg->
getName());
125 if (sampler->configure(jc))
128 "Temporary sampler satisfying joint constraints for group '%s' allocated. "
129 "Looking for different types of constraints before returning though.",
131 joint_sampler = sampler;
136 std::vector<ConstraintSamplerPtr> samplers;
138 samplers.push_back(joint_sampler);
149 "There is an IK allocator for '%s'. "
150 "Checking for corresponding position and/or orientation constraints",
154 std::map<std::string, IKConstraintSamplerPtr> used_l;
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)
164 kinematic_constraints::PositionConstraintPtr pc(
166 kinematic_constraints::OrientationConstraintPtr oc(
168 if (pc->configure(constr.position_constraints[
p],
scene->getTransforms()) &&
169 oc->configure(constr.orientation_constraints[o],
scene->getTransforms()))
171 IKConstraintSamplerPtr iks = std::make_shared<IKConstraintSampler>(
scene, jmg->
getName());
176 if (used_l.find(constr.position_constraints[
p].link_name) != used_l.end())
178 if (used_l[constr.position_constraints[
p].link_name]->getSamplingVolume() < iks->getSamplingVolume())
183 used_l[constr.position_constraints[
p].link_name] = iks;
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());
194 std::map<std::string, IKConstraintSamplerPtr> used_l_full_pose = used_l;
196 for (
const moveit_msgs::msg::PositionConstraint& position_constraint : constr.position_constraints)
200 if (used_l_full_pose.find(position_constraint.link_name) != used_l_full_pose.end())
203 kinematic_constraints::PositionConstraintPtr pc(
205 if (pc->configure(position_constraint,
scene->getTransforms()))
207 IKConstraintSamplerPtr iks = std::make_shared<IKConstraintSampler>(
scene, jmg->
getName());
211 if (used_l.find(position_constraint.link_name) != used_l.end())
212 if (used_l[position_constraint.link_name]->getSamplingVolume() < iks->getSamplingVolume())
216 used_l[position_constraint.link_name] = iks;
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());
226 for (
const moveit_msgs::msg::OrientationConstraint& orientation_constraint : constr.orientation_constraints)
230 if (used_l_full_pose.find(orientation_constraint.link_name) != used_l_full_pose.end())
233 kinematic_constraints::OrientationConstraintPtr oc(
235 if (oc->configure(orientation_constraint,
scene->getTransforms()))
237 IKConstraintSamplerPtr iks = std::make_shared<IKConstraintSampler>(
scene, jmg->
getName());
241 if (used_l.find(orientation_constraint.link_name) != used_l.end())
242 if (used_l[orientation_constraint.link_name]->getSamplingVolume() < iks->getSamplingVolume())
246 used_l[orientation_constraint.link_name] = iks;
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());
256 if (used_l.size() == 1)
258 if (samplers.empty())
259 return used_l.begin()->second;
262 samplers.push_back(used_l.begin()->second);
263 return std::make_shared<UnionConstraintSampler>(
scene, jmg->
getName(), samplers);
266 else if (used_l.size() > 1)
268 RCLCPP_DEBUG(LOGGER,
"Too many IK-based samplers for group '%s'. Keeping the one with minimal sampling volume",
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)
275 double v = it->second->getSamplingVolume();
282 if (samplers.empty())
288 samplers.push_back(iks);
289 return std::make_shared<UnionConstraintSampler>(
scene, jmg->
getName(), samplers);
296 if (!ik_subgroup_alloc.empty())
299 "There are IK allocators for subgroups of group '%s'. "
300 "Checking for corresponding position and/or orientation constraints",
303 bool some_sampler_valid =
false;
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)
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())
315 sub_constr.position_constraints.push_back(constr.position_constraints[
p]);
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())
323 sub_constr.orientation_constraints.push_back(constr.orientation_constraints[o]);
328 if (!sub_constr.orientation_constraints.empty() || !sub_constr.position_constraints.empty())
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());
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);
344 if (some_sampler_valid)
346 RCLCPP_DEBUG(LOGGER,
"Constructing sampler for group '%s' as a union of %zu samplers", jmg->
getName().c_str(),
348 return std::make_shared<UnionConstraintSampler>(
scene, jmg->
getName(), samplers);
355 RCLCPP_DEBUG(LOGGER,
"Allocated a sampler satisfying joint constraints for group '%s'", jmg->
getName().c_str());
356 return joint_sampler;
359 RCLCPP_DEBUG(LOGGER,
"No constraints sampler allocated for group '%s'", jmg->
getName().c_str());
361 return ConstraintSamplerPtr();
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...
A structure for potentially holding a position constraint and an orientation constraint for use durin...