moveit2
The MoveIt Motion Planning Framework for ROS 2.
default_constraint_samplers.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 <random_numbers/random_numbers.h>
42 #include <rclcpp/rclcpp.hpp>
43 #include <string>
44 #include <Eigen/Geometry>
45 
46 namespace constraint_samplers
47 {
48 MOVEIT_CLASS_FORWARD(JointConstraintSampler); // Defines JointConstraintSamplerPtr, ConstPtr, WeakPtr... etc
49 
60 {
61 public:
72  JointConstraintSampler(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name)
73  : ConstraintSampler(scene, group_name), random_number_generator_(random_numbers::RandomNumberGenerator())
74  {
75  }
76 
89  JointConstraintSampler(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name,
90  unsigned int seed)
91  : ConstraintSampler(scene, group_name), random_number_generator_(random_numbers::RandomNumberGenerator(seed))
92  {
93  }
94 
112  bool configure(const moveit_msgs::msg::Constraints& constr) override;
113 
139  bool configure(const std::vector<kinematic_constraints::JointConstraint>& jc);
140 
141  bool sample(moveit::core::RobotState& state, const moveit::core::RobotState& ks, unsigned int max_attempts) override;
142 
143  bool project(moveit::core::RobotState& state, unsigned int max_attempts) override;
144 
152  std::size_t getConstrainedJointCount() const
153  {
154  return bounds_.size();
155  }
156 
163  std::size_t getUnconstrainedJointCount() const
164  {
165  return unbounded_.size();
166  }
167 
173  const std::string& getName() const override
174  {
175  static const std::string SAMPLER_NAME = "JointConstraintSampler";
176  return SAMPLER_NAME;
177  }
178 
179 protected:
181  struct JointInfo
182  {
189  {
190  min_bound_ = -std::numeric_limits<double>::max();
191  max_bound_ = std::numeric_limits<double>::max();
192  }
193 
203  void potentiallyAdjustMinMaxBounds(double min, double max)
204  {
205  min_bound_ = std::max(min, min_bound_);
206  max_bound_ = std::min(max, max_bound_);
207  }
208 
209  double min_bound_;
210  double max_bound_;
211  std::size_t index_;
212  };
213 
214  void clear() override;
215 
216  random_numbers::RandomNumberGenerator random_number_generator_;
217  std::vector<JointInfo> bounds_;
220  std::vector<const moveit::core::JointModel*> unbounded_;
222  std::vector<unsigned int> uindex_;
223  std::vector<double> values_;
224 };
225 
232 {
238  IKSamplingPose();
239 
247 
256 
268 
276  IKSamplingPose(const kinematic_constraints::PositionConstraintPtr& pc);
277 
285  IKSamplingPose(const kinematic_constraints::OrientationConstraintPtr& oc);
286 
295  IKSamplingPose(const kinematic_constraints::PositionConstraintPtr& pc,
296  const kinematic_constraints::OrientationConstraintPtr& oc);
297 
298  kinematic_constraints::PositionConstraintPtr position_constraint_;
300  kinematic_constraints::OrientationConstraintPtr
302 };
303 
304 MOVEIT_CLASS_FORWARD(IKConstraintSampler); // Defines IKConstraintSamplerPtr, ConstPtr, WeakPtr... etc
305 
315 {
316 public:
327  IKConstraintSampler(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name)
328  : ConstraintSampler(scene, group_name), random_number_generator_(random_numbers::RandomNumberGenerator())
329  {
330  }
331 
344  IKConstraintSampler(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name,
345  unsigned int seed)
346  : ConstraintSampler(scene, group_name), random_number_generator_(random_numbers::RandomNumberGenerator(seed))
347  {
348  }
349 
374  bool configure(const moveit_msgs::msg::Constraints& constr) override;
375 
400  bool configure(const IKSamplingPose& sp);
401 
408  double getIKTimeout() const
409  {
410  return ik_timeout_;
411  }
412 
418  void setIKTimeout(double timeout)
419  {
420  ik_timeout_ = timeout;
421  }
422 
429  const kinematic_constraints::PositionConstraintPtr& getPositionConstraint() const
430  {
432  }
439  const kinematic_constraints::OrientationConstraintPtr& getOrientationConstraint() const
440  {
442  }
443 
457  double getSamplingVolume() const;
458 
465  const std::string& getLinkName() const;
466 
488  bool sample(moveit::core::RobotState& state, const moveit::core::RobotState& reference_state,
489  unsigned int max_attempts) override;
490 
491  bool project(moveit::core::RobotState& state, unsigned int max_attempts) override;
514  bool samplePose(Eigen::Vector3d& pos, Eigen::Quaterniond& quat, const moveit::core::RobotState& ks,
515  unsigned int max_attempts);
516 
522  const std::string& getName() const override
523  {
524  static const std::string SAMPLER_NAME = "IKConstraintSampler";
525  return SAMPLER_NAME;
526  }
527 
528 protected:
529  void clear() override;
530 
537  bool loadIKSolver();
538 
549  bool callIK(const geometry_msgs::msg::Pose& ik_query,
550  const kinematics::KinematicsBase::IKCallbackFn& adapted_ik_validity_callback, double timeout,
551  moveit::core::RobotState& state, bool use_as_seed);
552  bool sampleHelper(moveit::core::RobotState& state, const moveit::core::RobotState& reference_state,
553  unsigned int max_attempts, bool project);
554  bool validate(moveit::core::RobotState& state) const;
555 
556  random_numbers::RandomNumberGenerator random_number_generator_;
558  kinematics::KinematicsBaseConstPtr kb_;
559  double ik_timeout_;
560  std::string ik_frame_;
565  Eigen::Isometry3d eef_to_ik_tip_transform_;
566 };
567 } // namespace constraint_samplers
ConstraintSampler is an abstract base class that allows the sampling of a kinematic state for a parti...
A class that allows the sampling of IK constraints.
bool configure(const moveit_msgs::msg::Constraints &constr) override
Configures the IK constraint given a constraints message.
double ik_timeout_
Holds the timeout associated with IK.
bool loadIKSolver()
Performs checks and sets various internal values associated with the IK solver.
const std::string & getLinkName() const
Gets the link name associated with this sampler.
bool validate(moveit::core::RobotState &state) const
IKSamplingPose sampling_pose_
Holder for the pose used for sampling.
const kinematic_constraints::PositionConstraintPtr & getPositionConstraint() const
Gets the position constraint associated with this sampler.
double getIKTimeout() const
Gets the timeout argument passed to the IK solver.
IKConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
Constructor.
bool callIK(const geometry_msgs::msg::Pose &ik_query, const kinematics::KinematicsBase::IKCallbackFn &adapted_ik_validity_callback, double timeout, moveit::core::RobotState &state, bool use_as_seed)
Actually calls IK on the given pose, generating a random seed state.
double getSamplingVolume() const
Gets the volume associated with the position and orientation constraints.
Eigen::Isometry3d eef_to_ik_tip_transform_
Holds the transformation from end effector to IK tip frame.
void setIKTimeout(double timeout)
Sets the timeout argument passed to the IK solver.
bool need_eef_to_ik_tip_transform_
True if the tip frame of the inverse kinematic is different than the frame of the end effector.
IKConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, unsigned int seed)
Constructor.
kinematics::KinematicsBaseConstPtr kb_
Holds the kinematics solver.
void clear() override
Clears all data from the constraint.
std::string ik_frame_
Holds the base from of the IK solver.
random_numbers::RandomNumberGenerator random_number_generator_
Random generator used by the sampler.
bool project(moveit::core::RobotState &state, unsigned int max_attempts) override
Project a sample given the constraints, updating the joint state group. This function allows the para...
const kinematic_constraints::OrientationConstraintPtr & getOrientationConstraint() const
Gets the orientation constraint associated with this sampler.
bool transform_ik_
True if the frame associated with the kinematic model is different than the base frame of the IK solv...
bool sample(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts) override
Produces an IK sample.
const std::string & getName() const override
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
bool sampleHelper(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts, bool project)
bool samplePose(Eigen::Vector3d &pos, Eigen::Quaterniond &quat, const moveit::core::RobotState &ks, unsigned int max_attempts)
Returns a pose that falls within the constraint regions.
JointConstraintSampler is a class that allows the sampling of joints in a particular group of the rob...
std::vector< unsigned int > uindex_
The index of the unbounded joints in the joint state vector.
JointConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, unsigned int seed)
bool project(moveit::core::RobotState &state, unsigned int max_attempts) override
Project a sample given the constraints, updating the joint state group. This function allows the para...
void clear() override
Clears all data from the constraint.
JointConstraintSampler(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name)
std::size_t getUnconstrainedJointCount() const
Gets the number of unconstrained joints - joint that have no additional bound beyond the joint limits...
random_numbers::RandomNumberGenerator random_number_generator_
Random number generator used to sample.
std::vector< const moveit::core::JointModel * > unbounded_
The joints that are not bounded except by joint limits.
bool configure(const moveit_msgs::msg::Constraints &constr) override
Configures a joint constraint given a Constraints message.
std::vector< JointInfo > bounds_
The bounds for any joint with bounds that are more restrictive than the joint limits.
bool sample(moveit::core::RobotState &state, const moveit::core::RobotState &ks, unsigned int max_attempts) override
Samples given the constraints, populating state. This function allows the parameter max_attempts to b...
std::vector< double > values_
Values associated with this group to avoid continuously reallocating.
const std::string & getName() const override
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
std::size_t getConstrainedJointCount() const
Gets the number of constrained joints - joints that have an additional bound beyond the joint limits.
Class for constraints on the orientation of a link.
Class for constraints on the XYZ position of a link.
std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
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)
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
scene
Definition: pick.py:52
A structure for potentially holding a position constraint and an orientation constraint for use durin...
kinematic_constraints::PositionConstraintPtr position_constraint_
Holds the position constraint for sampling.
kinematic_constraints::OrientationConstraintPtr orientation_constraint_
Holds the orientation constraint for sampling.
An internal structure used for maintaining constraints on a particular joint.
void potentiallyAdjustMinMaxBounds(double min, double max)
Function that adjusts the joints only if they are more restrictive. This means that the min limit is ...