state_validity_checker.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 <ros/ros.h>
41 
42 namespace ompl_interface
43 {
44 constexpr char LOGNAME[] = "state_validity_checker";
45 } // namespace ompl_interface
46 
48  : ompl::base::StateValidityChecker(pc->getOMPLSimpleSetup()->getSpaceInformation())
49  , planning_context_(pc)
50  , group_name_(pc->getGroupName())
51  , tss_(pc->getCompleteInitialRobotState())
52  , verbose_(false)
53 {
54  specs_.clearanceComputationType = ompl::base::StateValidityCheckerSpecs::APPROXIMATE;
55  specs_.hasValidDirectionComputation = false;
56 
59 
63 
66 
69 }
70 
72 {
73  verbose_ = flag;
74 }
75 
76 bool ompl_interface::StateValidityChecker::isValid(const ompl::base::State* state, bool verbose) const
77 {
78  // Use cached validity if it is available
80  return state->as<ModelBasedStateSpace::StateType>()->isMarkedValid();
81 
82  if (!si_->satisfiesBounds(state))
83  {
84  if (verbose)
85  ROS_INFO_NAMED(LOGNAME, "State outside bounds");
86  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
87  return false;
88  }
89 
90  moveit::core::RobotState* robot_state = tss_.getStateStorage();
91  planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state);
92 
93  // check path constraints
94  const kinematic_constraints::KinematicConstraintSetPtr& kset = planning_context_->getPathConstraints();
95  if (kset && !kset->decide(*robot_state, verbose).satisfied)
96  {
97  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
98  return false;
99  }
100 
101  // check feasibility
102  if (!planning_context_->getPlanningScene()->isStateFeasible(*robot_state, verbose))
103  {
104  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
105  return false;
106  }
107 
108  // check collision avoidance
110  planning_context_->getPlanningScene()->checkCollision(
111  verbose ? collision_request_simple_verbose_ : collision_request_simple_, res, *robot_state);
112  if (!res.collision)
113  {
114  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markValid();
115  }
116  else
117  {
118  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
119  }
120  return !res.collision;
121 }
122 
123 bool ompl_interface::StateValidityChecker::isValid(const ompl::base::State* state, double& dist, bool verbose) const
124 {
125  // Use cached validity and distance if they are available
126  if (state->as<ModelBasedStateSpace::StateType>()->isValidityKnown() &&
128  {
129  dist = state->as<ModelBasedStateSpace::StateType>()->distance;
130  return state->as<ModelBasedStateSpace::StateType>()->isMarkedValid();
131  }
132 
133  if (!si_->satisfiesBounds(state))
134  {
135  if (verbose)
136  ROS_INFO_NAMED(LOGNAME, "State outside bounds");
137  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(0.0);
138  return false;
139  }
140 
141  moveit::core::RobotState* robot_state = tss_.getStateStorage();
142  planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state);
143 
144  // check path constraints
145  const kinematic_constraints::KinematicConstraintSetPtr& kset = planning_context_->getPathConstraints();
146  if (kset)
147  {
148  kinematic_constraints::ConstraintEvaluationResult cer = kset->decide(*robot_state, verbose);
149  if (!cer.satisfied)
150  {
151  dist = cer.distance;
152  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(dist);
153  return false;
154  }
155  }
156 
157  // check feasibility
158  if (!planning_context_->getPlanningScene()->isStateFeasible(*robot_state, verbose))
159  {
160  dist = 0.0;
161  return false;
162  }
163 
164  // check collision avoidance
166  planning_context_->getPlanningScene()->checkCollision(
167  verbose ? collision_request_with_distance_verbose_ : collision_request_with_distance_, res, *robot_state);
168  dist = res.distance;
169  return !res.collision;
170 }
171 
172 double ompl_interface::StateValidityChecker::cost(const ompl::base::State* state) const
173 {
174  double cost = 0.0;
175 
176  moveit::core::RobotState* robot_state = tss_.getStateStorage();
177  planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state);
178 
179  // Calculates cost from a summation of distance to obstacles times the size of the obstacle
181  planning_context_->getPlanningScene()->checkCollision(collision_request_with_cost_, res, *robot_state);
182 
183  for (const collision_detection::CostSource& cost_source : res.cost_sources)
184  cost += cost_source.cost * cost_source.getVolume();
185 
186  return cost;
187 }
188 
189 double ompl_interface::StateValidityChecker::clearance(const ompl::base::State* state) const
190 {
191  moveit::core::RobotState* robot_state = tss_.getStateStorage();
192  planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state);
193 
195  planning_context_->getPlanningScene()->checkCollision(collision_request_with_distance_, res, *robot_state);
196  return res.collision ? 0.0 : (res.distance < 0.0 ? std::numeric_limits<double>::infinity() : res.distance);
197 }
collision_detection::CostSource::cost
double cost
collision_detection::CollisionRequest::cost
bool cost
ompl_interface::StateValidityChecker::clearance
double clearance(const ompl::base::State *state) const override
Definition: state_validity_checker.cpp:189
model_based_planning_context.h
ompl_interface::StateValidityChecker::cost
virtual double cost(const ompl::base::State *state) const
Definition: state_validity_checker.cpp:172
ompl_interface::StateValidityChecker::planning_context_
const ModelBasedPlanningContext * planning_context_
Definition: state_validity_checker.h:110
ompl_interface::ModelBasedPlanningContext
Definition: model_based_planning_context.h:105
ros.h
ompl_interface
The MoveIt interface to OMPL.
Definition: constrained_goal_sampler.h:46
ompl_interface::ModelBasedStateSpace::StateType
Definition: model_based_state_space.h:109
moveit::core::RobotState
kinematic_constraints::ConstraintEvaluationResult::satisfied
bool satisfied
collision_detection::CostSource::getVolume
double getVolume() const
planning_interface::PlanningContext::getGroupName
const std::string & getGroupName() const
collision_detection::CostSource
collision_detection::CollisionRequest::distance
bool distance
kinematic_constraints::ConstraintEvaluationResult::distance
double distance
ompl_interface::ModelBasedStateSpace::StateType::isValidityKnown
bool isValidityKnown() const
Definition: model_based_state_space.h:150
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
collision_detection::CollisionResult
ompl_interface::StateValidityChecker
An interface for a OMPL state validity checker.
Definition: state_validity_checker.h:80
ompl_interface::LOGNAME
constexpr char LOGNAME[]
Definition: constrained_goal_sampler.cpp:78
ompl_interface::StateValidityChecker::collision_request_with_distance_
collision_detection::CollisionRequest collision_request_with_distance_
Definition: state_validity_checker.h:114
state_validity_checker.h
collision_detection::CollisionRequest::verbose
bool verbose
collision_detection::CollisionRequest::group_name
std::string group_name
ompl_interface::StateValidityChecker::setVerbose
void setVerbose(bool flag)
Definition: state_validity_checker.cpp:71
distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
ompl_interface::StateValidityChecker::collision_request_with_cost_
collision_detection::CollisionRequest collision_request_with_cost_
Definition: state_validity_checker.h:118
ompl_interface::StateValidityChecker::collision_request_simple_verbose_
collision_detection::CollisionRequest collision_request_simple_verbose_
Definition: state_validity_checker.h:115
ompl_interface::ModelBasedStateSpace::StateType::isGoalDistanceKnown
bool isGoalDistanceKnown() const
Definition: model_based_state_space.h:165
ompl_interface::StateValidityChecker::collision_request_simple_
collision_detection::CollisionRequest collision_request_simple_
Definition: state_validity_checker.h:113
collision_detection::CollisionResult::collision
bool collision
collision_detection::CollisionResult::cost_sources
std::set< CostSource > cost_sources
profiler.h
ompl_interface::StateValidityChecker::StateValidityChecker
StateValidityChecker(const ModelBasedPlanningContext *planning_context)
Definition: state_validity_checker.cpp:47
ompl_interface::StateValidityChecker::isValid
bool isValid(const ompl::base::State *state) const override
Definition: state_validity_checker.h:85
ompl_interface::StateValidityChecker::collision_request_with_distance_verbose_
collision_detection::CollisionRequest collision_request_with_distance_verbose_
Definition: state_validity_checker.h:116
collision_detection::CollisionResult::distance
double distance
verbose
bool verbose
kinematic_constraints::ConstraintEvaluationResult


ompl
Author(s): Ioan Sucan
autogenerated on Fri May 3 2024 02:29:39