55 kinematic_constraints::KinematicConstraintSetPtr ks,
56 constraint_samplers::ConstraintSamplerPtr cs)
57 : ob::GoalLazySamples(
58 pc->getOMPLSimpleSetup()->getSpaceInformation(),
59 [this](const GoalLazySamples* gls, ompl::base::State* state) {
60 return sampleUsingConstraintSampler(gls, state);
63 , planning_context_(pc)
64 , kinematic_constraint_set_(std::move(ks))
65 , constraint_sampler_(std::move(cs))
66 , work_state_(pc->getCompleteInitialRobotState())
67 , invalid_sampled_constraints_(0)
68 , warned_invalid_samples_(
false)
71 if (!constraint_sampler_)
72 default_sampler_ = si_->allocStateSampler();
73 RCLCPP_DEBUG(getLogger(),
"Constructed a ConstrainedGoalSampler instance at address %p",
this);
81 return static_cast<const StateValidityChecker*
>(si_->getStateValidityChecker().get())->isValid(new_goal, verbose);
90 solution_state.setJointGroupPositions(jmg, jpos);
91 solution_state.update();
92 return checkStateValidity(new_goal, solution_state, verbose);
95bool ConstrainedGoalSampler::sampleUsingConstraintSampler(
const ob::GoalLazySamples* gls, ob::State* new_goal)
98 unsigned int attempts_so_far = gls->samplingAttemptsCount();
101 if (attempts_so_far >= max_attempts)
112 unsigned int max_attempts_div2 = max_attempts / 2;
113 for (
unsigned int a = gls->samplingAttemptsCount(); a < max_attempts && gls->isSampling(); ++a)
115 bool verbose =
false;
116 if (gls->getStateCount() == 0 && a >= max_attempts_div2)
118 if (verbose_display_ < 1)
125 if (constraint_sampler_)
131 const double* joint_group_variable_values) {
132 return stateValidityCallback(new_goal, robot_state, joint_group, joint_group_variable_values, verbose);
134 constraint_sampler_->setGroupStateValidityCallback(gsvcf);
139 if (kinematic_constraint_set_->decide(work_state_, verbose).satisfied)
141 if (checkStateValidity(new_goal, work_state_, verbose))
146 invalid_sampled_constraints_++;
147 if (!warned_invalid_samples_ && invalid_sampled_constraints_ >= (attempts_so_far * 8) / 10)
149 warned_invalid_samples_ =
true;
150 RCLCPP_WARN(
getLogger(),
"More than 80%% of the sampled goal states "
151 "fail to satisfy the constraints imposed on the goal sampler. "
152 "Is the constrained sampler working correctly?");
159 default_sampler_->sampleUniform(new_goal);
160 if (
static_cast<const StateValidityChecker*
>(si_->getStateValidityChecker().get())->isValid(new_goal, verbose))
163 if (kinematic_constraint_set_->decide(work_state_, verbose).satisfied)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void update(bool force=false)
Update all transforms.
ConstrainedGoalSampler(const ModelBasedPlanningContext *pc, kinematic_constraints::KinematicConstraintSetPtr ks, constraint_samplers::ConstraintSamplerPtr cs=constraint_samplers::ConstraintSamplerPtr())
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
unsigned int getMaximumGoalSamplingAttempts() const
unsigned int getMaximumGoalSamples() const
unsigned int getMaximumStateSamplingAttempts() const
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
rclcpp::Logger getLogger()
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
The MoveIt interface to OMPL.