#include <constrained_goal_sampler.h>
Public Member Functions | |
ConstrainedGoalSampler (const ModelBasedPlanningContext *pc, const kinematic_constraints::KinematicConstraintSetPtr &ks, const constraint_samplers::ConstraintSamplerPtr &cs=constraint_samplers::ConstraintSamplerPtr()) | |
Private Member Functions | |
bool | checkStateValidity (ompl::base::State *new_goal, const robot_state::RobotState &state, bool verbose=false) const |
bool | sampleUsingConstraintSampler (const ompl::base::GoalLazySamples *gls, ompl::base::State *new_goal) |
bool | stateValidityCallback (ompl::base::State *new_goal, robot_state::RobotState const *state, const robot_model::JointModelGroup *, const double *, bool verbose=false) const |
Private Attributes | |
constraint_samplers::ConstraintSamplerPtr | constraint_sampler_ |
ompl::base::StateSamplerPtr | default_sampler_ |
unsigned int | invalid_sampled_constraints_ |
kinematic_constraints::KinematicConstraintSetPtr | kinematic_constraint_set_ |
const ModelBasedPlanningContext * | planning_context_ |
unsigned int | verbose_display_ |
bool | warned_invalid_samples_ |
robot_state::RobotState | work_state_ |
An interface to the OMPL goal lazy sampler
Definition at line 54 of file constrained_goal_sampler.h.
ompl_interface::ConstrainedGoalSampler::ConstrainedGoalSampler | ( | const ModelBasedPlanningContext * | pc, |
const kinematic_constraints::KinematicConstraintSetPtr & | ks, | ||
const constraint_samplers::ConstraintSamplerPtr & | cs = constraint_samplers::ConstraintSamplerPtr() |
||
) |
Definition at line 42 of file constrained_goal_sampler.cpp.
bool ompl_interface::ConstrainedGoalSampler::checkStateValidity | ( | ompl::base::State * | new_goal, |
const robot_state::RobotState & | state, | ||
bool | verbose = false |
||
) | const [private] |
Definition at line 61 of file constrained_goal_sampler.cpp.
bool ompl_interface::ConstrainedGoalSampler::sampleUsingConstraintSampler | ( | const ompl::base::GoalLazySamples * | gls, |
ompl::base::State * | new_goal | ||
) | [private] |
Definition at line 82 of file constrained_goal_sampler.cpp.
bool ompl_interface::ConstrainedGoalSampler::stateValidityCallback | ( | ompl::base::State * | new_goal, |
robot_state::RobotState const * | state, | ||
const robot_model::JointModelGroup * | , | ||
const double * | , | ||
bool | verbose = false |
||
) | const [private] |
Definition at line 69 of file constrained_goal_sampler.cpp.
constraint_samplers::ConstraintSamplerPtr ompl_interface::ConstrainedGoalSampler::constraint_sampler_ [private] |
Definition at line 70 of file constrained_goal_sampler.h.
ompl::base::StateSamplerPtr ompl_interface::ConstrainedGoalSampler::default_sampler_ [private] |
Definition at line 71 of file constrained_goal_sampler.h.
unsigned int ompl_interface::ConstrainedGoalSampler::invalid_sampled_constraints_ [private] |
Definition at line 73 of file constrained_goal_sampler.h.
kinematic_constraints::KinematicConstraintSetPtr ompl_interface::ConstrainedGoalSampler::kinematic_constraint_set_ [private] |
Definition at line 69 of file constrained_goal_sampler.h.
const ModelBasedPlanningContext* ompl_interface::ConstrainedGoalSampler::planning_context_ [private] |
Definition at line 68 of file constrained_goal_sampler.h.
unsigned int ompl_interface::ConstrainedGoalSampler::verbose_display_ [private] |
Definition at line 75 of file constrained_goal_sampler.h.
Definition at line 74 of file constrained_goal_sampler.h.
robot_state::RobotState ompl_interface::ConstrainedGoalSampler::work_state_ [private] |
Definition at line 72 of file constrained_goal_sampler.h.