moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
46namespace constraint_samplers
47{
48MOVEIT_CLASS_FORWARD(JointConstraintSampler); // Defines JointConstraintSamplerPtr, ConstPtr, WeakPtr... etc
49
60{
61public:
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
150 std::size_t getConstrainedJointCount() const
151 {
152 return bounds_.size();
153 }
154
161 std::size_t getUnconstrainedJointCount() const
162 {
163 return unbounded_.size();
164 }
165
171 const std::string& getName() const override
172 {
173 static const std::string SAMPLER_NAME = "JointConstraintSampler";
174 return SAMPLER_NAME;
175 }
176
177protected:
180 {
187 {
188 min_bound_ = -std::numeric_limits<double>::max();
189 max_bound_ = std::numeric_limits<double>::max();
190 }
191
201 void potentiallyAdjustMinMaxBounds(double min, double max)
202 {
203 min_bound_ = std::max(min, min_bound_);
204 max_bound_ = std::min(max, max_bound_);
205 }
206
207 double min_bound_;
208 double max_bound_;
209 std::size_t index_;
210 };
211
212 void clear() override;
213
214 random_numbers::RandomNumberGenerator random_number_generator_;
215 std::vector<JointInfo> bounds_;
218 std::vector<const moveit::core::JointModel*> unbounded_;
220 std::vector<unsigned int> uindex_;
221 std::vector<double> values_;
222};
223
230{
237
245
254
266
274 IKSamplingPose(const kinematic_constraints::PositionConstraintPtr& pc);
275
283 IKSamplingPose(const kinematic_constraints::OrientationConstraintPtr& oc);
284
293 IKSamplingPose(const kinematic_constraints::PositionConstraintPtr& pc,
294 const kinematic_constraints::OrientationConstraintPtr& oc);
295
296 kinematic_constraints::PositionConstraintPtr position_constraint_;
298 kinematic_constraints::OrientationConstraintPtr
300};
301
302MOVEIT_CLASS_FORWARD(IKConstraintSampler); // Defines IKConstraintSamplerPtr, ConstPtr, WeakPtr... etc
303
313{
314public:
325 IKConstraintSampler(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name)
326 : ConstraintSampler(scene, group_name), random_number_generator_(random_numbers::RandomNumberGenerator())
327 {
328 }
329
342 IKConstraintSampler(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name,
343 unsigned int seed)
344 : ConstraintSampler(scene, group_name), random_number_generator_(random_numbers::RandomNumberGenerator(seed))
345 {
346 }
347
372 bool configure(const moveit_msgs::msg::Constraints& constr) override;
373
398 bool configure(const IKSamplingPose& sp);
399
406 double getIKTimeout() const
407 {
408 return ik_timeout_;
409 }
410
416 void setIKTimeout(double timeout)
417 {
418 ik_timeout_ = timeout;
419 }
420
427 const kinematic_constraints::PositionConstraintPtr& getPositionConstraint() const
428 {
430 }
437 const kinematic_constraints::OrientationConstraintPtr& getOrientationConstraint() const
438 {
440 }
441
455 double getSamplingVolume() const;
456
463 const std::string& getLinkName() const;
464
486 bool sample(moveit::core::RobotState& state, const moveit::core::RobotState& reference_state,
487 unsigned int max_attempts) override;
488
511 bool samplePose(Eigen::Vector3d& pos, Eigen::Quaterniond& quat, const moveit::core::RobotState& ks,
512 unsigned int max_attempts);
513
519 const std::string& getName() const override
520 {
521 static const std::string SAMPLER_NAME = "IKConstraintSampler";
522 return SAMPLER_NAME;
523 }
524
525protected:
526 void clear() override;
527
534 bool loadIKSolver();
535
546 bool callIK(const geometry_msgs::msg::Pose& ik_query,
547 const kinematics::KinematicsBase::IKCallbackFn& adapted_ik_validity_callback, double timeout,
548 moveit::core::RobotState& state, bool use_as_seed);
549 bool sampleHelper(moveit::core::RobotState& state, const moveit::core::RobotState& reference_state,
550 unsigned int max_attempts);
551 bool validate(moveit::core::RobotState& state) const;
552
553 random_numbers::RandomNumberGenerator random_number_generator_;
555 kinematics::KinematicsBaseConstPtr kb_;
556 double ik_timeout_;
557 std::string ik_frame_;
562 Eigen::Isometry3d eef_to_ik_tip_transform_;
563};
564} // namespace constraint_samplers
#define MOVEIT_CLASS_FORWARD(C)
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.
const kinematic_constraints::PositionConstraintPtr & getPositionConstraint() const
Gets the position constraint associated with this sampler.
const std::string & getName() const override
Get the name of the constraint sampler, for debugging purposes should be in CamelCase format.
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.
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.
const kinematic_constraints::OrientationConstraintPtr & getOrientationConstraint() const
Gets the orientation constraint associated with this sampler.
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.
bool sampleHelper(moveit::core::RobotState &state, const moveit::core::RobotState &reference_state, unsigned int max_attempts)
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 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.
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)
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...
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 ...