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