moveit2
The MoveIt Motion Planning Framework for ROS 2.
cartesian_interpolator.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
5  * Copyright (c) 2013, Willow Garage, Inc.
6  * Copyright (c) 2019, PickNik Inc.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage, Inc. nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *********************************************************************/
36 
37 /* Author: Ioan Sucan, Mike Lautman */
38 
39 #pragma once
40 
42 
43 namespace moveit
44 {
45 namespace core
46 {
49 {
50  double translational = 0.001; //< max deviation in translation (meters)
51  double rotational = 0.01; //< max deviation in rotation (radians)
52  double max_resolution = 1e-5; //< max resolution for waypoints (fraction of total path)
53 };
54 
57 {
58  JumpThreshold() = default; // default is equivalent to disabled().
59 
61  static JumpThreshold disabled();
62 
69  static JumpThreshold relative(double relative_factor);
70 
75  static JumpThreshold absolute(double revolute, double prismatic);
76 
77  double relative_factor = 0.0;
78  double revolute = 0.0; // Radians
79  double prismatic = 0.0; // Meters
80 
81  // Deprecated constructors. Construct using the builder methods above.
82  [[deprecated("Use JumpThreshold::relative() instead.")]] JumpThreshold(double relative_factor);
83  [[deprecated("Use JumpThreshold::absolute() instead.")]] JumpThreshold(double revolute, double prismatic);
84 };
85 
91 struct MaxEEFStep
92 {
94  {
95  }
96 
97  MaxEEFStep(double step_size) : translation(step_size), rotation(3.5 * step_size) // 0.035 rad = 2 deg
98  {
99  }
100 
101  double translation; // Meters
102  double rotation; // Radians
103 };
104 
106 {
107  // TODO(mlautman): Eventually, this planner should be moved out of robot_state
108 
109 public:
110  struct Percentage
111  {
112  // value must be in [0,1]
114  {
115  if (value < 0.0 || value > 1.0)
116  throw std::runtime_error("Percentage values must be between 0 and 1, inclusive");
117  }
118  operator double() const
119  {
120  return value;
121  }
122  double operator*() const
123  {
124  return value;
125  }
127  {
128  Percentage res(value * p.value);
129  return res;
130  }
131  double value;
132  };
133 
134  struct Distance
135  {
137  {
138  }
139  operator double() const
140  {
141  return meters;
142  }
143  double operator*() const
144  {
145  return meters;
146  }
147  Distance operator*(const Percentage& p) const
148  {
149  Distance res(meters * p.value);
150  return res;
151  }
152  double meters;
153  };
154 
172  const RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& traj,
173  const LinkModel* link, const Eigen::Vector3d& translation, bool global_reference_frame,
174  const MaxEEFStep& max_step, const CartesianPrecision& precision,
178 
184  const RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& traj,
185  const LinkModel* link, const Eigen::Vector3d& direction, bool global_reference_frame, double distance,
186  const MaxEEFStep& max_step, const CartesianPrecision& precision,
190  {
191  return computeCartesianPath(start_state, group, traj, link, distance * direction, global_reference_frame, max_step,
192  precision, validCallback, options, cost_function);
193  }
194 
201  static Percentage computeCartesianPath(
202  const RobotState* start_state, const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
203  const LinkModel* link, const Eigen::Isometry3d& target, bool global_reference_frame, const MaxEEFStep& max_step,
204  const CartesianPrecision& precision, const GroupStateValidityCallbackFn& validCallback,
207  const Eigen::Isometry3d& link_offset = Eigen::Isometry3d::Identity());
208 
216  const RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& traj,
217  const LinkModel* link, const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame,
218  const MaxEEFStep& max_step, const CartesianPrecision& precision,
222  const Eigen::Isometry3d& link_offset = Eigen::Isometry3d::Identity());
223 
250  [[deprecated("Replace JumpThreshold with CartesianPrecision")]] static Distance computeCartesianPath(
251  RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& path,
252  const LinkModel* link, const Eigen::Vector3d& translation, bool global_reference_frame,
253  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
257 
262  [[deprecated("Replace JumpThreshold with CartesianPrecision")]] static Distance computeCartesianPath(
263  RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& path,
264  const LinkModel* link, const Eigen::Vector3d& direction, bool global_reference_frame, double distance,
265  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
269  {
270 #pragma GCC diagnostic push
271 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
272  return computeCartesianPath(start_state, group, path, link, distance * direction, global_reference_frame, max_step,
273  jump_threshold, validCallback, options, cost_function);
274 #pragma GCC diagnostic pop
275  }
276 
284  [[deprecated("Replace JumpThreshold with CartesianPrecision")]] static Percentage computeCartesianPath(
285  RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& path,
286  const LinkModel* link, const Eigen::Isometry3d& target, bool global_reference_frame, const MaxEEFStep& max_step,
287  const JumpThreshold& jump_threshold,
291  const Eigen::Isometry3d& link_offset = Eigen::Isometry3d::Identity());
292 
299  [[deprecated("Replace JumpThreshold with CartesianPrecision")]] static Percentage computeCartesianPath(
300  RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& path,
301  const LinkModel* link, const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame,
302  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
306  const Eigen::Isometry3d& link_offset = Eigen::Isometry3d::Identity());
307 
318  static Percentage checkJointSpaceJump(const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& path,
319  const JumpThreshold& jump_threshold);
320 };
321 
328 std::optional<int> hasJointSpaceJump(const std::vector<moveit::core::RobotStatePtr>& waypoints,
329  const moveit::core::JointModelGroup& group,
330  const moveit::core::JumpThreshold& jump_threshold);
331 
332 } // end of namespace core
333 } // end of namespace moveit
std::function< double(const geometry_msgs::msg::Pose &, const moveit::core::RobotState &, const moveit::core::JointModelGroup *, const std::vector< double > &)> IKCostFn
Signature for a cost function used to evaluate IK solutions.
static Percentage computeCartesianPath(const RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, const LinkModel *link, const EigenSTL::vector_Isometry3d &waypoints, bool global_reference_frame, const MaxEEFStep &max_step, const CartesianPrecision &precision, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn(), const Eigen::Isometry3d &link_offset=Eigen::Isometry3d::Identity())
Compute the sequence of joint values that perform a general Cartesian path.
static Distance computeCartesianPath(const RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, const LinkModel *link, const Eigen::Vector3d &direction, bool global_reference_frame, double distance, const MaxEEFStep &max_step, const CartesianPrecision &precision, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
Compute the sequence of joint values that correspond to a straight Cartesian path,...
static Percentage computeCartesianPath(RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &path, const LinkModel *link, const Eigen::Isometry3d &target, bool global_reference_frame, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn(), const Eigen::Isometry3d &link_offset=Eigen::Isometry3d::Identity())
Compute the sequence of joint values that correspond to a straight Cartesian path,...
static Distance computeCartesianPath(const RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, const LinkModel *link, const Eigen::Vector3d &translation, bool global_reference_frame, const MaxEEFStep &max_step, const CartesianPrecision &precision, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular li...
static Distance computeCartesianPath(RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &path, const LinkModel *link, const Eigen::Vector3d &translation, bool global_reference_frame, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular li...
static Percentage checkJointSpaceJump(const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &path, const JumpThreshold &jump_threshold)
Checks if a path has a joint-space jump, and truncates the path at the jump.
static Percentage computeCartesianPath(RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &path, const LinkModel *link, const EigenSTL::vector_Isometry3d &waypoints, bool global_reference_frame, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn(), const Eigen::Isometry3d &link_offset=Eigen::Isometry3d::Identity())
Compute the sequence of joint values that perform a general Cartesian path.
static Distance computeCartesianPath(RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &path, const LinkModel *link, const Eigen::Vector3d &direction, bool global_reference_frame, double distance, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
Compute the sequence of joint values that correspond to a straight Cartesian path,...
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.hpp:72
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.hpp:90
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.hpp:89
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.hpp:70
std::optional< int > hasJointSpaceJump(const std::vector< moveit::core::RobotStatePtr > &waypoints, const moveit::core::JointModelGroup &group, const moveit::core::JumpThreshold &jump_threshold)
Checks if a joint-space path has a jump larger than the given threshold.
Main namespace for MoveIt.
Definition: exceptions.hpp:43
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.hpp:59
A set of options for the kinematics solver.
Percentage operator*(const Percentage &p) const
Struct with options for defining joint-space jump thresholds.
static JumpThreshold relative(double relative_factor)
Detect joint-space jumps relative to the average joint-space displacement along the path.
static JumpThreshold absolute(double revolute, double prismatic)
Detect joint-space jumps greater than the given absolute thresholds.
static JumpThreshold disabled()
Do not define any jump threshold, i.e., disable joint-space jump detection.
Struct for containing max_step for computeCartesianPath.
MaxEEFStep(double translation, double rotation)