37 #ifndef MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_ 38 #define MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_ 76 ConstraintSampler(
const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group_name);
90 virtual bool configure(
const moveit_msgs::Constraints& constr) = 0;
172 return sample(state, state, DEFAULT_MAX_SAMPLING_ATTEMPTS);
188 return sample(state, state, max_attempts);
203 return sample(state, reference_state, DEFAULT_MAX_SAMPLING_ATTEMPTS);
218 return project(state, DEFAULT_MAX_SAMPLING_ATTEMPTS);
233 unsigned int max_attempts) = 0;
277 virtual const std::string&
getName()
const = 0;
284 virtual void clear();
289 planning_scene::PlanningSceneConstPtr
scene_;
static const unsigned int DEFAULT_MAX_SAMPLING_ATTEMPTS
The default value associated with a sampling request. By default if a valid sample cannot be produced...
virtual ~ConstraintSampler()
bool isValid() const
Returns whether or not the constraint sampler is valid or not. To be valid, the joint model group mus...
virtual void setVerbose(bool verbose)
Enable/disable verbose mode for sampler.
virtual const std::string & getName() const =0
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format...
bool project(robot_state::RobotState &state)
Project a sample given the constraints, updating the joint state group. The value DEFAULT_MAX_SAMPLIN...
MOVEIT_CLASS_FORWARD(ConstraintSampler)
const std::string & getGroupName() const
Gets the group name set in the constructor.
virtual void clear()
Clears all data from the constraint.
ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a parti...
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Gets the planning scene.
const std::vector< std::string > & getFrameDependency() const
Return the names of the mobile frames whose pose is needed when sample() is called.
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
void setGroupStateValidityCallback(const robot_state::GroupStateValidityCallbackFn &callback)
Sets the callback used to determine the state validity during sampling. The sampler will attempt to s...
bool verbose_
True if verbosity is on.
bool getVerbose() const
Check if the sampler is set to verbose mode.
const robot_state::GroupStateValidityCallbackFn & getGroupStateValidityCallback() const
Gets the callback used to determine state validity during sampling. The sampler will attempt to satis...
const std::string & getName() const
Get the name of the joint group.
ConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
Constructor.
robot_state::GroupStateValidityCallbackFn group_state_validity_callback_
Holds the callback for state validity.
bool sample(robot_state::RobotState &state, const robot_state::RobotState &reference_state)
Samples given the constraints, populating state. The value DEFAULT_MAX_SAMPLING_ATTEMPTS will be pass...
bool sample(robot_state::RobotState &state)
Samples given the constraints, populating state. The value DEFAULT_MAX_SAMPLING_ATTEMPTS will be pass...
bool sample(robot_state::RobotState &state, unsigned int max_attempts)
Samples given the constraints, populating state. This function allows the parameter max_attempts to b...
const robot_model::JointModelGroup *const jmg_
Holds the joint model group associated with this constraint.
virtual bool configure(const moveit_msgs::Constraints &constr)=0
Function for configuring a constraint sampler given a Constraints message.
std::vector< std::string > frame_depends_
Holds the set of frames that must exist in the reference state to allow samples to be drawn...
bool is_valid_
Holds the value for validity.
Representation of a robot's state. This includes position, velocity, acceleration and effort...
boost::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_...
planning_scene::PlanningSceneConstPtr scene_
Holds the planning scene.
const robot_model::JointModelGroup * getJointModelGroup() const
Gets the joint model group.