moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
constrained_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
40#include <utility>
41
43 constraint_samplers::ConstraintSamplerPtr cs)
44 : ob::StateSampler(pc->getOMPLStateSpace().get())
45 , planning_context_(pc)
46 , default_(space_->allocDefaultStateSampler())
47 , constraint_sampler_(std::move(cs))
48 , work_state_(pc->getCompleteInitialRobotState())
49 , constrained_success_(0)
50 , constrained_failure_(0)
51{
52 inv_dim_ = space_->getDimension() > 0 ? 1.0 / static_cast<double>(space_->getDimension()) : 1.0;
53}
54
56{
57 if (constrained_success_ == 0)
58 {
59 return 0.0;
60 }
61 else
62 {
63 return static_cast<double>(constrained_success_) / static_cast<double>(constrained_success_ + constrained_failure_);
64 }
65}
66
67bool ompl_interface::ConstrainedSampler::sampleC(ob::State* state)
68{
69 if (constraint_sampler_->sample(work_state_, planning_context_->getCompleteInitialRobotState(),
70 planning_context_->getMaximumStateSamplingAttempts()))
71 {
72 planning_context_->getOMPLStateSpace()->copyToOMPLState(state, work_state_);
73 if (space_->satisfiesBounds(state))
74 {
75 ++constrained_success_;
76 return true;
77 }
78 }
79 ++constrained_failure_;
80 return false;
81}
82
84{
85 if (!sampleC(state) && !sampleC(state) && !sampleC(state))
86 default_->sampleUniform(state);
87}
88
89void ompl_interface::ConstrainedSampler::sampleUniformNear(ob::State* state, const ob::State* near,
90 const double distance)
91{
92 if (sampleC(state) || sampleC(state) || sampleC(state))
93 {
94 double total_d = space_->distance(state, near);
95 if (total_d > distance)
96 {
97 double dist = pow(rng_.uniform01(), inv_dim_) * distance;
98 space_->interpolate(near, state, dist / total_d, state);
99 }
100 }
101 else
102 default_->sampleUniformNear(state, near, distance);
103}
104
105void ompl_interface::ConstrainedSampler::sampleGaussian(ob::State* state, const ob::State* mean, const double stdDev)
106{
107 if (sampleC(state) || sampleC(state) || sampleC(state))
108 {
109 double total_d = space_->distance(state, mean);
110 double distance = rng_.gaussian(0.0, stdDev);
111 if (total_d > distance)
112 {
113 double dist = pow(rng_.uniform01(), inv_dim_) * distance;
114 space_->interpolate(mean, state, dist / total_d, state);
115 }
116 }
117 else
118 default_->sampleGaussian(state, mean, stdDev);
119}
void sampleUniformNear(ompl::base::State *state, const ompl::base::State *near, const double distance) override
Sample a state (uniformly) within a certain distance of another state.
void sampleUniform(ompl::base::State *state) override
Sample a state (uniformly)
void sampleGaussian(ompl::base::State *state, const ompl::base::State *mean, const double stdDev) override
Sample a state using the specified Gaussian.
ConstrainedSampler(const ModelBasedPlanningContext *pc, constraint_samplers::ConstraintSamplerPtr cs)
Default constructor.