moveit2
The MoveIt Motion Planning Framework for ROS 2.
constraint_sampler.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
41 #include <vector>
42 #include <rclcpp/rclcpp.hpp>
52 {
53 MOVEIT_CLASS_FORWARD(ConstraintSampler); // Defines ConstraintSamplerPtr, ConstPtr, WeakPtr... etc
54 
60 {
61 public:
64  static const unsigned int DEFAULT_MAX_SAMPLING_ATTEMPTS = 2;
65 
75  ConstraintSampler(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name);
76 
78  {
79  }
80 
89  virtual bool configure(const moveit_msgs::msg::Constraints& constr) = 0;
90 
96  const std::string& getGroupName() const
97  {
98  return getJointModelGroup()->getName();
99  }
100 
108  {
109  return jmg_;
110  }
111 
118  const planning_scene::PlanningSceneConstPtr& getPlanningScene() const
119  {
120  return scene_;
121  }
122 
134  const std::vector<std::string>& getFrameDependency() const
135  {
136  return frame_depends_;
137  }
138 
144  {
146  }
147 
155  {
157  }
158 
170  {
171  return sample(state, state, DEFAULT_MAX_SAMPLING_ATTEMPTS);
172  }
173 
185  bool sample(moveit::core::RobotState& state, unsigned int max_attempts)
186  {
187  return sample(state, state, max_attempts);
188  }
189 
200  bool sample(moveit::core::RobotState& state, const moveit::core::RobotState& reference_state)
201  {
202  return sample(state, reference_state, DEFAULT_MAX_SAMPLING_ATTEMPTS);
203  }
204 
216  virtual bool sample(moveit::core::RobotState& state, const moveit::core::RobotState& reference_state,
217  unsigned int max_attempts) = 0;
218 
226  bool isValid() const
227  {
228  return is_valid_;
229  }
230 
232  bool getVerbose() const
233  {
234  return verbose_;
235  }
236 
238  virtual void setVerbose(bool verbose)
239  {
240  verbose_ = verbose;
241  }
242 
248  virtual const std::string& getName() const = 0;
249 
250 protected:
255  virtual void clear();
256 
257  bool is_valid_;
258 
260  planning_scene::PlanningSceneConstPtr scene_;
264  std::vector<std::string> frame_depends_;
267  bool verbose_;
268 };
269 } // namespace constraint_samplers
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.
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.
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...
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.
Definition: robot_state.h:90
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_...
Definition: robot_state.h:70