45 bool operator()(
const ConstraintSamplerPtr& a,
const ConstraintSamplerPtr& b)
const
47 const std::vector<std::string>& alinks = a->getJointModelGroup()->getUpdatedLinkModelNames();
48 const std::vector<std::string>& blinks = b->getJointModelGroup()->getUpdatedLinkModelNames();
49 std::set<std::string> a_updates(alinks.begin(), alinks.end());
50 std::set<std::string> b_updates(blinks.begin(), blinks.end());
52 bool a_contains_b = std::includes(a_updates.begin(), a_updates.end(), b_updates.begin(), b_updates.end());
54 bool b_contains_a = std::includes(b_updates.begin(), b_updates.end(), a_updates.begin(), a_updates.end());
57 if (a_contains_b && !b_contains_a)
59 if (b_contains_a && !a_contains_b)
63 bool a_depends_on_b =
false;
64 bool b_depends_on_a =
false;
65 const std::vector<std::string>& fda = a->getFrameDependency();
66 const std::vector<std::string>& fdb = b->getFrameDependency();
67 for (std::size_t i = 0; i < fda.size() && !a_depends_on_b; ++i)
68 for (
const std::string& blink : blinks)
71 a_depends_on_b =
true;
74 for (std::size_t i = 0; i < fdb.size() && !b_depends_on_a; ++i)
75 for (
const std::string& alink : alinks)
78 b_depends_on_a =
true;
81 if (b_depends_on_a && a_depends_on_b)
84 "Circular frame dependency! "
85 "Sampling will likely produce invalid results (sampling for groups '%s' and '%s')",
86 a->getJointModelGroup()->getName().c_str(), b->getJointModelGroup()->getName().c_str());
89 if (b_depends_on_a && !a_depends_on_b)
91 if (a_depends_on_b && !b_depends_on_a)
95 JointConstraintSampler* ja =
dynamic_cast<JointConstraintSampler*
>(a.get());
96 JointConstraintSampler* jb =
dynamic_cast<JointConstraintSampler*
>(b.get());
97 if (ja && jb ==
nullptr)
99 if (jb && ja ==
nullptr)
103 return (a->getJointModelGroup()->getName() < b->getJointModelGroup()->getName());
108 const std::string& group_name,
109 const std::vector<ConstraintSamplerPtr>& samplers)
113 std::stable_sort(samplers_.begin(), samplers_.end(),
OrderSamplers());
115 for (ConstraintSamplerPtr& sampler : samplers_)
117 const std::vector<std::string>& fds = sampler->getFrameDependency();
118 for (
const std::string& fd : fds)
119 frame_depends_.push_back(fd);
121 ROS_DEBUG_NAMED(
"constraint_samplers",
"Union sampler for group '%s' includes sampler for group '%s'",
122 jmg_->getName().c_str(), sampler->getJointModelGroup()->getName().c_str());
127 unsigned int max_attempts)
129 state = reference_state;
130 for (ConstraintSamplerPtr& sampler :
samplers_)
136 if (!sampler->sample(state, max_attempts))