moveit2
The MoveIt Motion Planning Framework for ROS 2.
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, Jeroen De Maeyer */
36 
39 #include <ompl/base/spaces/constraint/ConstrainedStateSpace.h>
40 #include <rclcpp/logger.hpp>
41 #include <rclcpp/logging.hpp>
42 
43 namespace ompl_interface
44 {
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.state_validity_checker");
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 StateValidityChecker::isValid(const ompl::base::State* state, bool verbose) const
77 {
78  assert(state != nullptr);
79  // Use cached validity if it is available
81  {
82  return state->as<ModelBasedStateSpace::StateType>()->isMarkedValid();
83  }
84 
85  if (!si_->satisfiesBounds(state))
86  {
87  if (verbose)
88  {
89  RCLCPP_INFO(LOGGER, "State outside bounds");
90  }
91  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
92  return false;
93  }
94 
96  planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state);
97 
98  // check path constraints
99  const kinematic_constraints::KinematicConstraintSetPtr& kset = planning_context_->getPathConstraints();
100  if (kset && !kset->decide(*robot_state, verbose).satisfied)
101  {
102  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
103  return false;
104  }
105 
106  // check feasibility
107  if (!planning_context_->getPlanningScene()->isStateFeasible(*robot_state, verbose))
108  {
109  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
110  return false;
111  }
112 
113  // check collision avoidance
115  planning_context_->getPlanningScene()->checkCollision(
116  verbose ? collision_request_simple_verbose_ : collision_request_simple_, res, *robot_state);
117  if (!res.collision)
118  {
119  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markValid();
120  }
121  else
122  {
123  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
124  }
125  return !res.collision;
126 }
127 
128 bool StateValidityChecker::isValid(const ompl::base::State* state, double& dist, bool verbose) const
129 {
130  assert(state != nullptr);
131  // Use cached validity and distance if they are available
132  if (state->as<ModelBasedStateSpace::StateType>()->isValidityKnown() &&
134  {
135  dist = state->as<ModelBasedStateSpace::StateType>()->distance;
136  return state->as<ModelBasedStateSpace::StateType>()->isMarkedValid();
137  }
138 
139  if (!si_->satisfiesBounds(state))
140  {
141  if (verbose)
142  {
143  RCLCPP_INFO(LOGGER, "State outside bounds");
144  }
145  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(0.0);
146  return false;
147  }
148 
150  planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state);
151 
152  // check path constraints
153  const kinematic_constraints::KinematicConstraintSetPtr& kset = planning_context_->getPathConstraints();
154  if (kset)
155  {
156  kinematic_constraints::ConstraintEvaluationResult cer = kset->decide(*robot_state, verbose);
157  if (!cer.satisfied)
158  {
159  dist = cer.distance;
160  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(dist);
161  return false;
162  }
163  }
164 
165  // check feasibility
166  if (!planning_context_->getPlanningScene()->isStateFeasible(*robot_state, verbose))
167  {
168  dist = 0.0;
169  return false;
170  }
171 
172  // check collision avoidance
174  planning_context_->getPlanningScene()->checkCollision(
176  dist = res.distance;
177  return !res.collision;
178 }
179 
180 double StateValidityChecker::cost(const ompl::base::State* state) const
181 {
182  assert(state != nullptr);
183  double cost = 0.0;
184 
186  planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state);
187 
188  // Calculates cost from a summation of distance to obstacles times the size of the obstacle
190  planning_context_->getPlanningScene()->checkCollision(collision_request_with_cost_, res, *robot_state);
191 
192  for (const collision_detection::CostSource& cost_source : res.cost_sources)
193  {
194  cost += cost_source.cost * cost_source.getVolume();
195  }
196 
197  return cost;
198 }
199 
200 double StateValidityChecker::clearance(const ompl::base::State* state) const
201 {
202  assert(state != nullptr);
204  planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state);
205 
207  planning_context_->getPlanningScene()->checkCollision(collision_request_with_distance_, res, *robot_state);
208  return res.collision ? 0.0 : (res.distance < 0.0 ? std::numeric_limits<double>::infinity() : res.distance);
209 }
210 
211 /*******************************************
212  * Constrained Planning StateValidityChecker
213  * *****************************************/
214 bool ConstrainedPlanningStateValidityChecker::isValid(const ompl::base::State* wrapped_state, bool verbose) const
215 {
216  assert(wrapped_state != nullptr);
217  // Unwrap the state from a ConstrainedStateSpace::StateType
218  auto state = wrapped_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState();
219 
220  // Use cached validity if it is available
222  {
223  return state->as<ModelBasedStateSpace::StateType>()->isMarkedValid();
224  }
225 
226  // do not use the unwrapped state here, as satisfiesBounds expects a state of type ConstrainedStateSpace::StateType
227  if (!si_->satisfiesBounds(wrapped_state)) // si_ = ompl::base::SpaceInformation
228  {
229  RCLCPP_DEBUG(LOGGER, "State outside bounds");
230  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
231  return false;
232  }
233 
235  // do not use the unwrapped state here, as copyToRobotState expects a state of type ConstrainedStateSpace::StateType
236  planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, wrapped_state);
237 
238  // check path constraints
239  const kinematic_constraints::KinematicConstraintSetPtr& kset = planning_context_->getPathConstraints();
240  if (kset && !kset->decide(*robot_state, verbose).satisfied)
241  {
242  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
243  return false;
244  }
245 
246  // check feasibility
247  if (!planning_context_->getPlanningScene()->isStateFeasible(*robot_state, verbose))
248  {
249  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
250  return false;
251  }
252 
253  // check collision avoidance
255  planning_context_->getPlanningScene()->checkCollision(
256  verbose ? collision_request_simple_verbose_ : collision_request_simple_, res, *robot_state);
257  if (!res.collision)
258  {
259  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markValid();
260  }
261  else
262  {
263  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
264  }
265  return !res.collision;
266 }
267 
268 bool ConstrainedPlanningStateValidityChecker::isValid(const ompl::base::State* wrapped_state, double& dist,
269  bool verbose) const
270 {
271  assert(wrapped_state != nullptr);
272  // Unwrap the state from a ConstrainedStateSpace::StateType
273  auto state = wrapped_state->as<ompl::base::ConstrainedStateSpace::StateType>()->getState();
274 
275  // Use cached validity and distance if they are available
276  if (state->as<ModelBasedStateSpace::StateType>()->isValidityKnown() &&
278  {
279  dist = state->as<ModelBasedStateSpace::StateType>()->distance;
280  return state->as<ModelBasedStateSpace::StateType>()->isMarkedValid();
281  }
282 
283  // do not use the unwrapped state here, as satisfiesBounds expects a state of type ConstrainedStateSpace::StateType
284  if (!si_->satisfiesBounds(wrapped_state)) // si_ = ompl::base::SpaceInformation
285  {
286  RCLCPP_DEBUG(LOGGER, "State outside bounds");
287  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid(0.0);
288  return false;
289  }
290 
292 
293  // do not use the unwrapped state here, as copyToRobotState expects a state of type ConstrainedStateSpace::StateType
294  planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, wrapped_state);
295 
296  // check path constraints
297  const kinematic_constraints::KinematicConstraintSetPtr& kset = planning_context_->getPathConstraints();
298  if (kset && !kset->decide(*robot_state, verbose).satisfied)
299  {
300  const_cast<ob::State*>(state)->as<ModelBasedStateSpace::StateType>()->markInvalid();
301  return false;
302  }
303 
304  // check feasibility
305  if (!planning_context_->getPlanningScene()->isStateFeasible(*robot_state, verbose))
306  {
307  dist = 0.0;
308  return false;
309  }
310 
311  // check collision avoidance
313  planning_context_->getPlanningScene()->checkCollision(
315  dist = res.distance;
316  return !res.collision;
317 }
318 } // namespace ompl_interface
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
bool isValid(const ompl::base::State *state) const override
const kinematic_constraints::KinematicConstraintSetPtr & getPathConstraints() const
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
An interface for a OMPL state validity checker.
collision_detection::CollisionRequest collision_request_simple_
StateValidityChecker(const ModelBasedPlanningContext *planning_context)
const ModelBasedPlanningContext * planning_context_
double clearance(const ompl::base::State *state) const override
virtual double cost(const ompl::base::State *state) const
bool isValid(const ompl::base::State *state) const override
collision_detection::CollisionRequest collision_request_with_distance_
collision_detection::CollisionRequest collision_request_with_cost_
collision_detection::CollisionRequest collision_request_with_distance_verbose_
collision_detection::CollisionRequest collision_request_simple_verbose_
moveit::core::RobotState * getStateStorage() const
const std::string & getGroupName() const
Get the name of the group this planning context is for.
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
The MoveIt interface to OMPL.
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
bool verbose
Flag indicating whether information about detected collisions should be reported.
bool cost
If true, a collision cost is computed.
bool distance
If true, compute proximity distance.
Representation of a collision checking result.
std::set< CostSource > cost_sources
These are the individual cost sources when costs are computed.
double distance
Closest distance between two bodies.
bool collision
True if collision was found, false otherwise.
When collision costs are computed, this structure contains information about the partial cost incurre...
double getVolume() const
Get the volume of the AABB around the cost source.
double cost
The partial cost (the probability of existence for the object there is a collision with)
Struct for containing the results of constraint evaluation.
bool satisfied
Whether or not the constraint or constraints were satisfied.
double distance
The distance evaluation from the constraint or constraints.
bool getState(const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Request > &request, const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Response > &response, moveit_warehouse::RobotStateStorage &rs)