Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_OMPL_INTERFACE_DETAIL_STATE_VALIDITY_CHECKER_
00038 #define MOVEIT_OMPL_INTERFACE_DETAIL_STATE_VALIDITY_CHECKER_
00039
00040 #include <moveit/ompl_interface/detail/threadsafe_state_storage.h>
00041 #include <moveit/collision_detection/collision_common.h>
00042 #include <ompl/base/StateValidityChecker.h>
00043
00044 namespace ompl_interface
00045 {
00046
00047 class ModelBasedPlanningContext;
00048
00051 class StateValidityChecker : public ompl::base::StateValidityChecker
00052 {
00053 public:
00054
00055 StateValidityChecker(const ModelBasedPlanningContext *planning_context);
00056
00057
00058 virtual bool isValid(const ompl::base::State *state) const
00059 {
00060 return isValid(state, verbose_);
00061 }
00062
00063 virtual bool isValid(const ompl::base::State *state, double &dist) const
00064 {
00065 return isValid(state, dist, verbose_);
00066 }
00067
00068 bool isValid(const ompl::base::State *state, bool verbose) const;
00069 bool isValid(const ompl::base::State *state, double &dist, bool verbose) const;
00070
00071 virtual double cost(const ompl::base::State *state) const;
00072 virtual double clearance(const ompl::base::State *state) const;
00073
00074 void setVerbose(bool flag);
00075
00076 protected:
00077
00078 bool isValidWithoutCache(const ompl::base::State *state, bool verbose) const;
00079 bool isValidWithoutCache(const ompl::base::State *state, double &dist, bool verbose) const;
00080
00081 bool isValidWithCache(const ompl::base::State *state, bool verbose) const;
00082 bool isValidWithCache(const ompl::base::State *state, double &dist, bool verbose) const;
00083
00084 const ModelBasedPlanningContext *planning_context_;
00085 std::string group_name_;
00086 TSStateStorage tss_;
00087 collision_detection::CollisionRequest collision_request_simple_;
00088 collision_detection::CollisionRequest collision_request_with_distance_;
00089 collision_detection::CollisionRequest collision_request_simple_verbose_;
00090 collision_detection::CollisionRequest collision_request_with_distance_verbose_;
00091
00092 collision_detection::CollisionRequest collision_request_with_cost_;
00093 bool verbose_;
00094 };
00095
00096 }
00097
00098 #endif