| 
    moveit2
    
   The MoveIt Motion Planning Framework for ROS 2. 
   | 
 
#include <constrained_sampler.h>


Public Member Functions | |
| ConstrainedSampler (const ModelBasedPlanningContext *pc, constraint_samplers::ConstraintSamplerPtr cs) | |
| Default constructor.  More... | |
| void | sampleUniform (ompl::base::State *state) override | 
| Sample a state (uniformly)  More... | |
| void | sampleUniformNear (ompl::base::State *state, const ompl::base::State *near, const double distance) override | 
| Sample a state (uniformly) within a certain distance of another state.  More... | |
| void | sampleGaussian (ompl::base::State *state, const ompl::base::State *mean, const double stdDev) override | 
| Sample a state using the specified Gaussian.  More... | |
| double | getConstrainedSamplingRate () const | 
This class defines a sampler that tries to find a sample that satisfies the constraints
Definition at line 48 of file constrained_sampler.h.
| ompl_interface::ConstrainedSampler::ConstrainedSampler | ( | const ModelBasedPlanningContext * | pc, | 
| constraint_samplers::ConstraintSamplerPtr | cs | ||
| ) | 
Default constructor.
| pg | The planning group | 
| cs | A pointer to a kinematic constraint sampler | 
Definition at line 42 of file constrained_sampler.cpp.
| double ompl_interface::ConstrainedSampler::getConstrainedSamplingRate | ( | ) | const | 
Definition at line 55 of file constrained_sampler.cpp.
      
  | 
  override | 
Sample a state using the specified Gaussian.
Definition at line 101 of file constrained_sampler.cpp.

      
  | 
  override | 
Sample a state (uniformly)
Definition at line 79 of file constrained_sampler.cpp.
      
  | 
  override | 
Sample a state (uniformly) within a certain distance of another state.
Definition at line 85 of file constrained_sampler.cpp.
