moveit2
The MoveIt Motion Planning Framework for ROS 2.
union_constraint_sampler.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 
39 #include <rclcpp/logger.hpp>
40 #include <rclcpp/logging.hpp>
41 #include <algorithm>
42 
43 namespace constraint_samplers
44 {
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_constraint_samplers.union_constraint_sampler");
46 
48 {
49  bool operator()(const ConstraintSamplerPtr& a, const ConstraintSamplerPtr& b) const
50  {
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());
55 
56  bool a_contains_b = std::includes(a_updates.begin(), a_updates.end(), b_updates.begin(), b_updates.end());
57 
58  bool b_contains_a = std::includes(b_updates.begin(), b_updates.end(), a_updates.begin(), a_updates.end());
59 
60  // a contains b and sets are not equal
61  if (a_contains_b && !b_contains_a)
62  return true;
63  if (b_contains_a && !a_contains_b)
64  return false;
65 
66  // sets are equal or disjoint
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)
73  if (blink == fda[i])
74  {
75  a_depends_on_b = true;
76  break;
77  }
78  for (std::size_t i = 0; i < fdb.size() && !b_depends_on_a; ++i)
79  for (const std::string& alink : alinks)
80  if (alink == fdb[i])
81  {
82  b_depends_on_a = true;
83  break;
84  }
85  if (b_depends_on_a && a_depends_on_b)
86  {
87  RCLCPP_WARN(LOGGER,
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());
91  return true;
92  }
93  if (b_depends_on_a && !a_depends_on_b)
94  return true;
95  if (a_depends_on_b && !b_depends_on_a)
96  return false;
97 
98  // prefer sampling JointConstraints first
99  JointConstraintSampler* ja = dynamic_cast<JointConstraintSampler*>(a.get());
100  JointConstraintSampler* jb = dynamic_cast<JointConstraintSampler*>(b.get());
101  if (ja && jb == nullptr)
102  return true;
103  if (jb && ja == nullptr)
104  return false;
105 
106  // neither depends on either, so break ties based on group name
107  return (a->getJointModelGroup()->getName() < b->getJointModelGroup()->getName());
108  }
109 };
110 
111 UnionConstraintSampler::UnionConstraintSampler(const planning_scene::PlanningSceneConstPtr& scene,
112  const std::string& group_name,
113  const std::vector<ConstraintSamplerPtr>& samplers)
114  : ConstraintSampler(scene, group_name), samplers_(samplers)
115 {
116  // using stable sort to preserve order of equivalents
117  std::stable_sort(samplers_.begin(), samplers_.end(), OrderSamplers());
118 
119  for (ConstraintSamplerPtr& sampler : samplers_)
120  {
121  const std::vector<std::string>& fds = sampler->getFrameDependency();
122  for (const std::string& fd : fds)
123  frame_depends_.push_back(fd);
124 
125  RCLCPP_DEBUG(LOGGER, "Union sampler for group '%s' includes sampler for group '%s'", jmg_->getName().c_str(),
126  sampler->getJointModelGroup()->getName().c_str());
127  }
128 }
129 
131  unsigned int max_attempts)
132 {
133  state = reference_state;
134  state.setToRandomPositions(jmg_);
135 
136  if (!samplers_.empty())
137  {
138  if (!samplers_[0]->sample(state, reference_state, max_attempts))
139  return false;
140  }
141 
142  for (std::size_t i = 1; i < samplers_.size(); ++i)
143  {
144  // ConstraintSampler::sample returns states with dirty link transforms (because it only writes values)
145  // but requires a state with clean link transforms as input. This means that we need to clean the link
146  // transforms between calls to ConstraintSampler::sample.
147  state.updateLinkTransforms();
148  if (!samplers_[i]->sample(state, state, max_attempts))
149  return false;
150  }
151  return true;
152 }
153 
154 bool UnionConstraintSampler::project(moveit::core::RobotState& state, unsigned int max_attempts)
155 {
156  for (ConstraintSamplerPtr& sampler : samplers_)
157  {
158  // ConstraintSampler::project returns states with dirty link transforms (because it only writes values)
159  // but requires a state with clean link transforms as input. This means that we need to clean the link
160  // transforms between calls to ConstraintSampler::sample.
161  state.updateLinkTransforms();
162  if (!sampler->project(state, max_attempts))
163  return false;
164  }
165  return true;
166 }
167 
168 } // end of namespace constraint_samplers
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.
Definition: robot_state.h:90
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...
scene
Definition: pick.py:52
a
Definition: plan.py:54
bool operator()(const ConstraintSamplerPtr &a, const ConstraintSamplerPtr &b) const