moveit2
The MoveIt Motion Planning Framework for ROS 2.
constrained_goal_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 
40 #include <moveit/utils/logger.hpp>
41 
42 #include <utility>
43 
44 namespace ompl_interface
45 {
46 namespace
47 {
48 rclcpp::Logger getLogger()
49 {
50  return moveit::getLogger("ompl_constrained_goal_sampler");
51 }
52 } // namespace
53 
55  kinematic_constraints::KinematicConstraintSetPtr ks,
56  constraint_samplers::ConstraintSamplerPtr cs)
57  : ob::GoalLazySamples(
58  pc->getOMPLSimpleSetup()->getSpaceInformation(),
59  [this](const GoalLazySamples* gls, ompl::base::State* state) {
60  return sampleUsingConstraintSampler(gls, state);
61  },
62  false)
63  , planning_context_(pc)
64  , kinematic_constraint_set_(std::move(ks))
65  , constraint_sampler_(std::move(cs))
66  , work_state_(pc->getCompleteInitialRobotState())
67  , invalid_sampled_constraints_(0)
68  , warned_invalid_samples_(false)
69  , verbose_display_(0)
70 {
71  if (!constraint_sampler_)
72  default_sampler_ = si_->allocStateSampler();
73  RCLCPP_DEBUG(getLogger(), "Constructed a ConstrainedGoalSampler instance at address %p", this);
74  startSampling();
75 }
76 
77 bool ConstrainedGoalSampler::checkStateValidity(ob::State* new_goal, const moveit::core::RobotState& state,
78  bool verbose) const
79 {
80  planning_context_->getOMPLStateSpace()->copyToOMPLState(new_goal, state);
81  return static_cast<const StateValidityChecker*>(si_->getStateValidityChecker().get())->isValid(new_goal, verbose);
82 }
83 
84 bool ConstrainedGoalSampler::stateValidityCallback(ob::State* new_goal, const moveit::core::RobotState* state,
85  const moveit::core::JointModelGroup* jmg, const double* jpos,
86  bool verbose) const
87 {
88  // we copy the state to not change the seed state
89  moveit::core::RobotState solution_state(*state);
90  solution_state.setJointGroupPositions(jmg, jpos);
91  solution_state.update();
92  return checkStateValidity(new_goal, solution_state, verbose);
93 }
94 
95 bool ConstrainedGoalSampler::sampleUsingConstraintSampler(const ob::GoalLazySamples* gls, ob::State* new_goal)
96 {
97  unsigned int max_attempts = planning_context_->getMaximumGoalSamplingAttempts();
98  unsigned int attempts_so_far = gls->samplingAttemptsCount();
99 
100  // terminate after too many attempts
101  if (attempts_so_far >= max_attempts)
102  return false;
103 
104  // terminate after a maximum number of samples
105  if (gls->getStateCount() >= planning_context_->getMaximumGoalSamples())
106  return false;
107 
108  // terminate the sampling thread when a solution has been found
109  if (planning_context_->getOMPLSimpleSetup()->getProblemDefinition()->hasSolution())
110  return false;
111 
112  unsigned int max_attempts_div2 = max_attempts / 2;
113  for (unsigned int a = gls->samplingAttemptsCount(); a < max_attempts && gls->isSampling(); ++a)
114  {
115  bool verbose = false;
116  if (gls->getStateCount() == 0 && a >= max_attempts_div2)
117  {
118  if (verbose_display_ < 1)
119  {
120  verbose = true;
121  verbose_display_++;
122  }
123  }
124 
125  if (constraint_sampler_)
126  {
127  // makes the constraint sampler also perform a validity callback
128  moveit::core::GroupStateValidityCallbackFn gsvcf = [this, new_goal,
129  verbose](moveit::core::RobotState* robot_state,
130  const moveit::core::JointModelGroup* joint_group,
131  const double* joint_group_variable_values) {
132  return stateValidityCallback(new_goal, robot_state, joint_group, joint_group_variable_values, verbose);
133  };
134  constraint_sampler_->setGroupStateValidityCallback(gsvcf);
135 
136  if (constraint_sampler_->sample(work_state_, planning_context_->getMaximumStateSamplingAttempts()))
137  {
138  work_state_.update();
139  if (kinematic_constraint_set_->decide(work_state_, verbose).satisfied)
140  {
141  if (checkStateValidity(new_goal, work_state_, verbose))
142  return true;
143  }
144  else
145  {
146  invalid_sampled_constraints_++;
147  if (!warned_invalid_samples_ && invalid_sampled_constraints_ >= (attempts_so_far * 8) / 10)
148  {
149  warned_invalid_samples_ = true;
150  RCLCPP_WARN(getLogger(), "More than 80%% of the sampled goal states "
151  "fail to satisfy the constraints imposed on the goal sampler. "
152  "Is the constrained sampler working correctly?");
153  }
154  }
155  }
156  }
157  else
158  {
159  default_sampler_->sampleUniform(new_goal);
160  if (static_cast<const StateValidityChecker*>(si_->getStateValidityChecker().get())->isValid(new_goal, verbose))
161  {
162  planning_context_->getOMPLStateSpace()->copyToRobotState(work_state_, new_goal);
163  if (kinematic_constraint_set_->decide(work_state_, verbose).satisfied)
164  return true;
165  }
166  }
167  }
168  return false;
169 }
170 
171 } // namespace ompl_interface
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void update(bool force=false)
Update all transforms.
ConstrainedGoalSampler(const ModelBasedPlanningContext *pc, kinematic_constraints::KinematicConstraintSetPtr ks, constraint_samplers::ConstraintSamplerPtr cs=constraint_samplers::ConstraintSamplerPtr())
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
Definition: robot_state.h:70
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
The MoveIt interface to OMPL.