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...
|
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) |
| MOVEIT_CLASS_FORWARD (ConstraintSamplerManager) |
| MOVEIT_CLASS_FORWARD (ConstraintSamplerAllocator) |
| MOVEIT_CLASS_FORWARD (JointConstraintSampler) |
| MOVEIT_CLASS_FORWARD (ConstraintSampler) |
| MOVEIT_CLASS_FORWARD (IKConstraintSampler) |
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.