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