39 #include <rclcpp/logger.hpp>
40 #include <rclcpp/logging.hpp>
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_constraint_samplers.union_constraint_sampler");
49 bool operator()(
const ConstraintSamplerPtr&
a,
const ConstraintSamplerPtr& b)
const
51 const std::vector<std::string>& alinks =
a->getJointModelGroup()->getUpdatedLinkModelNames();
52 const std::vector<std::string>& blinks = b->getJointModelGroup()->getUpdatedLinkModelNames();
53 std::set<std::string> a_updates(alinks.begin(), alinks.end());
54 std::set<std::string> b_updates(blinks.begin(), blinks.end());
56 bool a_contains_b = std::includes(a_updates.begin(), a_updates.end(), b_updates.begin(), b_updates.end());
58 bool b_contains_a = std::includes(b_updates.begin(), b_updates.end(), a_updates.begin(), a_updates.end());
61 if (a_contains_b && !b_contains_a)
63 if (b_contains_a && !a_contains_b)
67 bool a_depends_on_b =
false;
68 bool b_depends_on_a =
false;
69 const std::vector<std::string>& fda =
a->getFrameDependency();
70 const std::vector<std::string>& fdb = b->getFrameDependency();
71 for (std::size_t i = 0; i < fda.size() && !a_depends_on_b; ++i)
72 for (
const std::string& blink : blinks)
75 a_depends_on_b =
true;
78 for (std::size_t i = 0; i < fdb.size() && !b_depends_on_a; ++i)
79 for (
const std::string& alink : alinks)
82 b_depends_on_a =
true;
85 if (b_depends_on_a && a_depends_on_b)
88 "Circular frame dependency! "
89 "Sampling will likely produce invalid results (sampling for groups '%s' and '%s')",
90 a->getJointModelGroup()->getName().c_str(), b->getJointModelGroup()->getName().c_str());
93 if (b_depends_on_a && !a_depends_on_b)
95 if (a_depends_on_b && !b_depends_on_a)
101 if (ja && jb ==
nullptr)
103 if (jb && ja ==
nullptr)
107 return (
a->getJointModelGroup()->getName() < b->getJointModelGroup()->getName());
112 const std::string& group_name,
113 const std::vector<ConstraintSamplerPtr>& samplers)
119 for (ConstraintSamplerPtr& sampler :
samplers_)
121 const std::vector<std::string>& fds = sampler->getFrameDependency();
122 for (
const std::string& fd : fds)
125 RCLCPP_DEBUG(LOGGER,
"Union sampler for group '%s' includes sampler for group '%s'",
jmg_->
getName().c_str(),
126 sampler->getJointModelGroup()->getName().c_str());
131 unsigned int max_attempts)
133 state = reference_state;
142 for (std::size_t i = 1; i <
samplers_.size(); ++i)
156 for (ConstraintSamplerPtr& sampler :
samplers_)
162 if (!sampler->project(state, max_attempts))
ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a parti...
std::vector< std::string > frame_depends_
Holds the set of frames that must exist in the reference state to allow samples to be drawn.
const moveit::core::JointModelGroup *const jmg_
Holds the joint model group associated with this constraint.
JointConstraintSampler is a class that allows the sampling of joints in a particular group of the rob...
bool sample(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts) override
Produces a sample from all configured samplers.
std::vector< ConstraintSamplerPtr > samplers_
Holder for sorted internal list of samplers.
bool project(moveit::core::RobotState &state, unsigned int max_attempts) override
Project a sample given the constraints, updating the joint state group. This function allows the para...
UnionConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::vector< ConstraintSamplerPtr > &samplers)
Constructor, which will re-order its internal list of samplers on construction.
const std::string & getName() const
Get the name of the joint group.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void updateLinkTransforms()
Update the reference frame transforms for links. This call is needed before using the transforms of l...
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
bool operator()(const ConstraintSamplerPtr &a, const ConstraintSamplerPtr &b) const