Go to the documentation of this file.
42 #include <ompl/base/StateStorage.h>
43 #include <boost/serialization/map.hpp>
47 typedef std::pair<std::vector<std::size_t>, std::map<std::size_t, std::pair<std::size_t, std::size_t> > >
53 class ConstraintApproximation
57 moveit_msgs::Constraints msg, std::string filename, ompl::base::StateStoragePtr storage,
58 std::size_t milestones = 0);
64 const std::string&
getName()
const
151 ConstraintApproximationPtr
approx;
173 const moveit_msgs::Constraints& constr_hard,
const std::string& group,
174 const planning_scene::PlanningSceneConstPtr& scene,
179 const planning_scene::PlanningSceneConstPtr& scene,
193 ompl::base::StateStoragePtr
195 const moveit_msgs::Constraints& constr_hard,
unsigned int max_explicit_points
ConstraintApproximationConstructionResults addConstraintApproximation(const moveit_msgs::Constraints &constr_sampling, const moveit_msgs::Constraints &constr_hard, const std::string &group, const planning_scene::PlanningSceneConstPtr &scene, const ConstraintApproximationConstructionOptions &options)
moveit_msgs::Constraints constraint_msg_
void loadConstraintApproximations(const std::string &path)
const std::string & getGroup() const
const std::string & getFilename() const
double state_connection_time
std::string ompldb_filename_
virtual ~ConstraintApproximation()
ompl::base::StateStoragePtr state_storage_ptr_
ompl::base::StateStoragePtr constructConstraintApproximation(ModelBasedPlanningContext *pcontext, const moveit_msgs::Constraints &constr_sampling, const moveit_msgs::Constraints &constr_hard, const ConstraintApproximationConstructionOptions &options, ConstraintApproximationConstructionResults &result)
The MoveIt interface to OMPL.
ConstraintApproximation(const planning_models::RobotModelConstPtr &kinematic_model, const std::string &group, const std::string &factory, const std::string &serialization, const std::string &filename, const ompl::base::StateStoragePtr &storage)
InterpolationFunction getInterpolationFunction() const
const std::vector< int > & getSpaceSignature() const
ConstraintApproximationPtr approx
std::string state_space_parameterization_
std::vector< int > space_signature_
std::pair< std::vector< std::size_t >, std::map< std::size_t, std::pair< std::size_t, std::size_t > > > ConstrainedStateMetadata
ConstraintApproximationStateStorage * state_storage_
ConstraintApproximationConstructionOptions()
ompl::base::StateSamplerAllocator getStateSamplerAllocator(const moveit_msgs::Constraints &msg) const
ompl::base::StateStorageWithMetadata< std::vector< std::size_t > > ConstraintApproximationStateStorage
const moveit_msgs::Constraints & getConstraintsMsg() const
bool hasExplicitMotions() const
void saveConstraintApproximations(const std::string &path)
void printConstraintApproximations(std::ostream &out=std::cout) const
void clearConstraintApproximations()
double sampling_success_rate
unsigned int edges_per_sample
ConstraintsLibrary(ModelBasedPlanningContext *pcontext)
double explicit_points_resolution
const ConstraintApproximationPtr & getConstraintApproximation(const moveit_msgs::Constraints &msg) const
const std::string & getName() const
void registerConstraintApproximation(const ConstraintApproximationPtr &approx)
const std::string & getStateSpaceParameterization() const
const ompl::base::StateStoragePtr & getStateStorage() const
std::size_t getMilestoneCount() const
MOVEIT_CLASS_FORWARD(ConstraintApproximation)
double state_sampling_time
std::string state_space_parameterization
std::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction
ModelBasedPlanningContext * context_
std::map< std::string, ConstraintApproximationPtr > constraint_approximations_
ompl
Author(s): Ioan Sucan
autogenerated on Tue Dec 24 2024 03:28:09