state_validity_checker.h
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 
37 #ifndef MOVEIT_OMPL_INTERFACE_DETAIL_STATE_VALIDITY_CHECKER_
38 #define MOVEIT_OMPL_INTERFACE_DETAIL_STATE_VALIDITY_CHECKER_
39 
41 #include <moveit/collision_detection/collision_common.h>
42 #include <ompl/base/StateValidityChecker.h>
43 
44 namespace ompl_interface
45 {
46 class ModelBasedPlanningContext;
47 
50 class StateValidityChecker : public ompl::base::StateValidityChecker
51 {
52 public:
53  StateValidityChecker(const ModelBasedPlanningContext* planning_context);
54 
55  virtual bool isValid(const ompl::base::State* state) const
56  {
57  return isValid(state, verbose_);
58  }
59 
60  virtual bool isValid(const ompl::base::State* state, double& dist) const
61  {
62  return isValid(state, dist, verbose_);
63  }
64 
65  bool isValid(const ompl::base::State* state, bool verbose) const;
66  bool isValid(const ompl::base::State* state, double& dist, bool verbose) const;
67 
68  virtual double cost(const ompl::base::State* state) const;
69  virtual double clearance(const ompl::base::State* state) const;
70 
71  void setVerbose(bool flag);
72 
73 protected:
74  bool isValidWithoutCache(const ompl::base::State* state, bool verbose) const;
75  bool isValidWithoutCache(const ompl::base::State* state, double& dist, bool verbose) const;
76 
77  bool isValidWithCache(const ompl::base::State* state, bool verbose) const;
78  bool isValidWithCache(const ompl::base::State* state, double& dist, bool verbose) const;
79 
81  std::string group_name_;
87 
89  bool verbose_;
90 };
91 }
92 
93 #endif
collision_detection::CollisionRequest collision_request_simple_verbose_
collision_detection::CollisionRequest collision_request_with_cost_
bool isValidWithCache(const ompl::base::State *state, bool verbose) const
collision_detection::CollisionRequest collision_request_simple_
virtual double cost(const ompl::base::State *state) const
collision_detection::CollisionRequest collision_request_with_distance_
StateValidityChecker(const ModelBasedPlanningContext *planning_context)
The MoveIt! interface to OMPL.
const ModelBasedPlanningContext * planning_context_
bool isValidWithoutCache(const ompl::base::State *state, bool verbose) const
virtual bool isValid(const ompl::base::State *state, double &dist) const
bool verbose
virtual double clearance(const ompl::base::State *state) const
collision_detection::CollisionRequest collision_request_with_distance_verbose_
An interface for a OMPL state validity checker.
virtual bool isValid(const ompl::base::State *state) const


ompl
Author(s): Ioan Sucan
autogenerated on Wed Jul 10 2019 04:03:46