37 #ifndef MOVEIT_OMPL_INTERFACE_DETAIL_CONSTRAINT_APPROXIMATION_ 38 #define MOVEIT_OMPL_INTERFACE_DETAIL_CONSTRAINT_APPROXIMATION_ 43 #include <ompl/base/StateStorage.h> 44 #include <visualization_msgs/MarkerArray.h> 45 #include <boost/function.hpp> 55 const std::string& factory,
const std::string& serialization,
const std::string&
filename,
56 const ompl::base::StateStoragePtr& storage);
58 const std::string& factory,
const moveit_msgs::Constraints& msg,
const std::string& filename,
59 const ompl::base::StateStoragePtr& storage);
62 visualization_msgs::MarkerArray& arr)
const;
68 planning_models::RobotModelConstPtr
kmodel_;
void visualizeDistribution(const std::string &link_name, unsigned int count, visualization_msgs::MarkerArray &arr) const
planning_models::RobotModelConstPtr kmodel_
std::vector< int > space_signature_
boost::function< bool(const ompl::base::State *, const ompl::base::State *)> ConstraintStateStorageOrderFn
moveit_msgs::Constraints constraint_msg_
The MoveIt! interface to OMPL.
ConstraintApproximationStateStorage * state_storage_
ompl::base::StateStoragePtr state_storage_ptr_
ConstraintApproximation(const std::string &group, const std::string &state_space_parameterization, bool explicit_motions, const moveit_msgs::Constraints &msg, const std::string &filename, const ompl::base::StateStoragePtr &storage, std::size_t milestones=0)
std::string serialization_
std::string ompldb_filename_
ompl::base::StateStorageWithMetadata< ConstrainedStateMetadata > ConstraintApproximationStateStorage
#define MOVEIT_DECLARE_PTR(Name, Type)
kinematic_constraints::KinematicConstraintSetPtr kconstraints_set_