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_CONSTRAINTS_LIBRARY_
00038 #define MOVEIT_OMPL_INTERFACE_CONSTRAINTS_LIBRARY_
00039
00040 #include <moveit/ompl_interface/planning_context_manager.h>
00041 #include <moveit/kinematic_constraints/kinematic_constraint.h>
00042 #include <ompl/base/StateStorage.h>
00043 #include <boost/function.hpp>
00044 #include <boost/serialization/map.hpp>
00045
00046 namespace ompl_interface
00047 {
00048
00049 typedef std::pair<std::vector<std::size_t>, std::map<std::size_t, std::pair<std::size_t, std::size_t> > > ConstrainedStateMetadata;
00050 typedef ompl::base::StateStorageWithMetadata<ConstrainedStateMetadata> ConstraintApproximationStateStorage;
00051
00052 class ConstraintApproximation;
00053 typedef boost::shared_ptr<ConstraintApproximation> ConstraintApproximationPtr;
00054 typedef boost::shared_ptr<const ConstraintApproximation> ConstraintApproximationConstPtr;
00055
00056 class ConstraintApproximation
00057 {
00058 public:
00059
00060 ConstraintApproximation(const std::string &group, const std::string &state_space_parameterization, bool explicit_motions,
00061 const moveit_msgs::Constraints &msg, const std::string &filename, const ompl::base::StateStoragePtr &storage,
00062 std::size_t milestones = 0);
00063
00064 virtual ~ConstraintApproximation()
00065 {
00066 }
00067
00068 const std::string& getName() const
00069 {
00070 return constraint_msg_.name;
00071 }
00072
00073 ompl::base::StateSamplerAllocator getStateSamplerAllocator(const moveit_msgs::Constraints &msg) const;
00074
00075 InterpolationFunction getInterpolationFunction() const;
00076
00077 const std::vector<int>& getSpaceSignature() const
00078 {
00079 return space_signature_;
00080 }
00081
00082 const std::string& getGroup() const
00083 {
00084 return group_;
00085 }
00086
00087 bool hasExplicitMotions() const
00088 {
00089 return explicit_motions_;
00090 }
00091
00092 std::size_t getMilestoneCount() const
00093 {
00094 return milestones_;
00095 }
00096
00097 const std::string& getStateSpaceParameterization() const
00098 {
00099 return state_space_parameterization_;
00100 }
00101
00102 const moveit_msgs::Constraints& getConstraintsMsg() const
00103 {
00104 return constraint_msg_;
00105 }
00106
00107 const ompl::base::StateStoragePtr& getStateStorage() const
00108 {
00109 return state_storage_ptr_;
00110 }
00111
00112 const std::string& getFilename() const
00113 {
00114 return ompldb_filename_;
00115 }
00116
00117 protected:
00118
00119 std::string group_;
00120 std::string state_space_parameterization_;
00121 bool explicit_motions_;
00122
00123 moveit_msgs::Constraints constraint_msg_;
00124
00125 std::vector<int> space_signature_;
00126
00127 std::string ompldb_filename_;
00128 ompl::base::StateStoragePtr state_storage_ptr_;
00129 ConstraintApproximationStateStorage *state_storage_;
00130 std::size_t milestones_;
00131 };
00132
00133 struct ConstraintApproximationConstructionOptions
00134 {
00135 ConstraintApproximationConstructionOptions() :
00136 samples(0),
00137 edges_per_sample(0),
00138 max_edge_length(std::numeric_limits<double>::infinity()),
00139 explicit_motions(false),
00140 explicit_points_resolution(0.0),
00141 max_explicit_points(0)
00142 {
00143 }
00144
00145 std::string state_space_parameterization;
00146 unsigned int samples;
00147 unsigned int edges_per_sample;
00148 double max_edge_length;
00149 bool explicit_motions;
00150 double explicit_points_resolution;
00151 unsigned int max_explicit_points;
00152 };
00153
00154 struct ConstraintApproximationConstructionResults
00155 {
00156 ConstraintApproximationPtr approx;
00157 std::size_t milestones;
00158 double state_sampling_time;
00159 double state_connection_time;
00160 double sampling_success_rate;
00161 };
00162
00163 class ConstraintsLibrary
00164 {
00165 public:
00166
00167 ConstraintsLibrary(const PlanningContextManager &pcontext) : context_manager_(pcontext)
00168 {
00169 }
00170
00171 void loadConstraintApproximations(const std::string &path);
00172
00173 void saveConstraintApproximations(const std::string &path);
00174
00175 ConstraintApproximationConstructionResults
00176 addConstraintApproximation(const moveit_msgs::Constraints &constr_sampling, const moveit_msgs::Constraints &constr_hard,
00177 const std::string &group, const planning_scene::PlanningSceneConstPtr &scene,
00178 const ConstraintApproximationConstructionOptions &options);
00179
00180 ConstraintApproximationConstructionResults
00181 addConstraintApproximation(const moveit_msgs::Constraints &constr,
00182 const std::string &group, const planning_scene::PlanningSceneConstPtr &scene,
00183 const ConstraintApproximationConstructionOptions &options);
00184
00185 void printConstraintApproximations(std::ostream &out = std::cout) const;
00186 void clearConstraintApproximations();
00187
00188 void registerConstraintApproximation(const ConstraintApproximationPtr &approx)
00189 {
00190 constraint_approximations_[approx->getName()] = approx;
00191 }
00192
00193 const ConstraintApproximationPtr& getConstraintApproximation(const moveit_msgs::Constraints &msg) const;
00194
00195 private:
00196
00197 ompl::base::StateStoragePtr constructConstraintApproximation(const ModelBasedPlanningContextPtr &pcontext,
00198 const moveit_msgs::Constraints &constr_sampling, const moveit_msgs::Constraints &constr_hard,
00199 const ConstraintApproximationConstructionOptions &options,
00200 ConstraintApproximationConstructionResults &result);
00201
00202 const PlanningContextManager &context_manager_;
00203 std::map<std::string, ConstraintApproximationPtr> constraint_approximations_;
00204
00205 };
00206
00207 typedef boost::shared_ptr<ConstraintsLibrary> ConstraintsLibraryPtr;
00208 typedef boost::shared_ptr<const ConstraintsLibrary> ConstraintsLibraryConstPtr;
00209
00210 }
00211
00212 #endif