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_CONSTRAINT_APPROXIMATION_
00038 #define MOVEIT_OMPL_INTERFACE_DETAIL_CONSTRAINT_APPROXIMATION_
00039
00040 #include <planning_scene/planning_scene.h>
00041 #include <kinematic_constraints/kinematic_constraint.h>
00042 #include <ompl/base/StateStorage.h>
00043 #include <visualization_msgs/MarkerArray.h>
00044 #include <boost/function.hpp>
00045
00046 namespace ompl_interface
00047 {
00048
00049 typedef ompl::base::StateStorageWithMetadata< std::vector<std::size_t> > ConstraintApproximationStateStorage;
00050 typedef boost::function<bool(const ompl::base::State*, const ompl::base::State*)> ConstraintStateStorageOrderFn;
00051
00052 struct ConstraintApproximation
00053 {
00054 ConstraintApproximation(const planning_models::RobotModelConstPtr &kinematic_model, const std::string &group, const std::string &factory,
00055 const std::string &serialization, const std::string &filename, const ompl::base::StateStoragePtr &storage);
00056 ConstraintApproximation(const planning_models::RobotModelConstPtr &kinematic_model, const std::string &group, const std::string &factory,
00057 const moveit_msgs::Constraints &msg, const std::string &filename, const ompl::base::StateStoragePtr &storage);
00058
00059 void visualizeDistribution(const std::string &link_name, unsigned int count, visualization_msgs::MarkerArray &arr) const;
00060
00061 std::string group_;
00062 std::string factory_;
00063 std::string serialization_;
00064 moveit_msgs::Constraints constraint_msg_;
00065 planning_models::RobotModelConstPtr kmodel_;
00066 kinematic_constraints::KinematicConstraintSetPtr kconstraints_set_;
00067 std::vector<int> space_signature_;
00068
00069 std::string ompldb_filename_;
00070 ompl::base::StateStoragePtr state_storage_ptr_;
00071 ConstraintApproximationStateStorage *state_storage_;
00072 };
00073
00074 typedef boost::shared_ptr<std::vector<ConstraintApproximation> > ConstraintApproximationsPtr;
00075 }
00076
00077 #endif