Go to the documentation of this file.
75 ConstraintSampler(
const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group_name);
89 virtual bool configure(
const moveit_msgs::Constraints& constr) = 0;
187 return sample(state, state, max_attempts);
217 unsigned int max_attempts) = 0;
248 virtual const std::string&
getName()
const = 0;
255 virtual void clear();
260 planning_scene::PlanningSceneConstPtr
scene_;
bool is_valid_
Holds the value for validity.
void setGroupStateValidityCallback(const moveit::core::GroupStateValidityCallbackFn &callback)
Sets the callback used to determine the state validity during sampling. The sampler will attempt to s...
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_...
virtual bool configure(const moveit_msgs::Constraints &constr)=0
Function for configuring a constraint sampler given a Constraints message.
virtual void setVerbose(bool verbose)
Enable/disable verbose mode for sampler.
const moveit::core::JointModelGroup *const jmg_
Holds the joint model group associated with this constraint.
const moveit::core::GroupStateValidityCallbackFn & getGroupStateValidityCallback() const
Gets the callback used to determine state validity during sampling. The sampler will attempt to satis...
bool sample(moveit::core::RobotState &state)
Samples given the constraints, populating state. The value DEFAULT_MAX_SAMPLING_ATTEMPTS will be pass...
const std::vector< std::string > & getFrameDependency() const
Return the names of the mobile frames whose pose is needed when sample() is called.
bool verbose_
True if verbosity is on.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const std::string & getGroupName() const
Gets the group name set in the constructor.
virtual const std::string & getName() const =0
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
const std::string & getName() const
Get the name of the joint group.
bool isValid() const
Returns whether or not the constraint sampler is valid or not. To be valid, the joint model group mus...
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...
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
std::vector< std::string > frame_depends_
Holds the set of frames that must exist in the reference state to allow samples to be drawn.
virtual void clear()
Clears all data from the constraint.
moveit::core::GroupStateValidityCallbackFn group_state_validity_callback_
Holds the callback for state validity.
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Gets the planning scene.
virtual ~ConstraintSampler()
const moveit::core::JointModelGroup * getJointModelGroup() const
Gets the joint model group.
planning_scene::PlanningSceneConstPtr scene_
Holds the planning scene.
ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a parti...
bool getVerbose() const
Check if the sampler is set to verbose mode.
MOVEIT_CLASS_FORWARD(ConstraintSampler)
ConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
Constructor.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14