The constraint samplers namespace contains a number of methods for generating samples based on a constraint or set of constraints. More...
Classes | |
class | ConstraintSampler |
ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a particular group of a robot. More... | |
class | ConstraintSamplerAllocator |
class | ConstraintSamplerManager |
This class assists in the generation of a ConstraintSampler for a particular group from a moveit_msgs::Constraints. More... | |
class | IKConstraintSampler |
A class that allows the sampling of IK constraints. More... | |
struct | IKSamplingPose |
A structure for potentially holding a position constraint and an orientation constraint for use during Ik Sampling. More... | |
class | JointConstraintSampler |
JointConstraintSampler is a class that allows the sampling of joints in a particular group of the robot, subject to a set of individual joint constraints. More... | |
struct | OrderSamplers |
class | UnionConstraintSampler |
This class exists as a union of constraint samplers. It contains a vector of constraint samplers, and will sample from each of them. More... | |
Typedefs | |
typedef boost::shared_ptr < const ConstraintSamplerAllocator > | ConstraintSamplerAllocatorConstPtr |
typedef boost::shared_ptr < ConstraintSamplerAllocator > | ConstraintSamplerAllocatorPtr |
typedef boost::shared_ptr < const ConstraintSampler > | ConstraintSamplerConstPtr |
boost shared_ptr to a const ConstraintSampler | |
typedef boost::shared_ptr < const ConstraintSamplerManager > | ConstraintSamplerManagerConstPtr |
boost::shared_ptr to a const ConstraintSamplerManager | |
typedef boost::shared_ptr < ConstraintSamplerManager > | ConstraintSamplerManagerPtr |
boost::shared_ptr to a ConstraintSamplerManager | |
typedef boost::shared_ptr < ConstraintSampler > | ConstraintSamplerPtr |
boost shared_ptr to a ConstraintSampler | |
Functions | |
double | countSamplesPerSecond (const ConstraintSamplerPtr &sampler, const robot_state::RobotState &reference_state) |
double | countSamplesPerSecond (const moveit_msgs::Constraints &constr, const planning_scene::PlanningSceneConstPtr &scene, const std::string &group) |
void | visualizeDistribution (const ConstraintSamplerPtr &sampler, const robot_state::RobotState &reference_state, const std::string &link_name, unsigned int sample_count, visualization_msgs::MarkerArray &markers) |
void | visualizeDistribution (const moveit_msgs::Constraints &constr, const planning_scene::PlanningSceneConstPtr &scene, const std::string &group, const std::string &link_name, unsigned int sample_count, visualization_msgs::MarkerArray &markers) |
The constraint samplers namespace contains a number of methods for generating samples based on a constraint or set of constraints.
It intended for use by any algorithm that requires a constraint-aware sampling strategy.
typedef boost::shared_ptr<const ConstraintSamplerAllocator> constraint_samplers::ConstraintSamplerAllocatorConstPtr |
Definition at line 63 of file constraint_sampler_allocator.h.
typedef boost::shared_ptr<ConstraintSamplerAllocator> constraint_samplers::ConstraintSamplerAllocatorPtr |
Definition at line 62 of file constraint_sampler_allocator.h.
typedef boost::shared_ptr<const ConstraintSampler> constraint_samplers::ConstraintSamplerConstPtr |
boost shared_ptr to a const ConstraintSampler
Definition at line 252 of file constraint_sampler.h.
typedef boost::shared_ptr<const ConstraintSamplerManager> constraint_samplers::ConstraintSamplerManagerConstPtr |
boost::shared_ptr to a const ConstraintSamplerManager
Definition at line 138 of file constraint_sampler_manager.h.
typedef boost::shared_ptr<ConstraintSamplerManager> constraint_samplers::ConstraintSamplerManagerPtr |
boost::shared_ptr to a ConstraintSamplerManager
Definition at line 137 of file constraint_sampler_manager.h.
typedef boost::shared_ptr<ConstraintSampler> constraint_samplers::ConstraintSamplerPtr |
boost shared_ptr to a ConstraintSampler
Definition at line 251 of file constraint_sampler.h.
double constraint_samplers::countSamplesPerSecond | ( | const ConstraintSamplerPtr & | sampler, |
const robot_state::RobotState & | reference_state | ||
) |
Definition at line 52 of file constraint_sampler_tools.cpp.
double constraint_samplers::countSamplesPerSecond | ( | const moveit_msgs::Constraints & | constr, |
const planning_scene::PlanningSceneConstPtr & | scene, | ||
const std::string & | group | ||
) |
Definition at line 47 of file constraint_sampler_tools.cpp.
void constraint_samplers::visualizeDistribution | ( | const ConstraintSamplerPtr & | sampler, |
const robot_state::RobotState & | reference_state, | ||
const std::string & | link_name, | ||
unsigned int | sample_count, | ||
visualization_msgs::MarkerArray & | markers | ||
) |
Definition at line 77 of file constraint_sampler_tools.cpp.
void constraint_samplers::visualizeDistribution | ( | const moveit_msgs::Constraints & | constr, |
const planning_scene::PlanningSceneConstPtr & | scene, | ||
const std::string & | group, | ||
const std::string & | link_name, | ||
unsigned int | sample_count, | ||
visualization_msgs::MarkerArray & | markers | ||
) |
Definition at line 40 of file constraint_sampler_tools.cpp.