moveit2
The MoveIt Motion Planning Framework for ROS 2.
cartesian_interpolator.h
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  JumpThreshold() = default; // default is equivalent to disabled().
51 
53  static JumpThreshold disabled();
54 
61  static JumpThreshold relative(double relative_factor);
62 
67  static JumpThreshold absolute(double revolute, double prismatic);
68 
69  double relative_factor = 0.0;
70  double revolute = 0.0; // Radians
71  double prismatic = 0.0; // Meters
72 
73  // Deprecated constructors. Construct using the builder methods above.
74  [[deprecated("Use JumpThreshold::relative() instead.")]] JumpThreshold(double relative_factor);
75  [[deprecated("Use JumpThreshold::absolute() instead.")]] JumpThreshold(double revolute, double prismatic);
76 };
77 
83 struct MaxEEFStep
84 {
86  {
87  }
88 
89  MaxEEFStep(double step_size) : translation(step_size), rotation(3.5 * step_size) // 0.035 rad = 2 deg
90  {
91  }
92 
93  double translation; // Meters
94  double rotation; // Radians
95 };
96 
98 {
99  // TODO(mlautman): Eventually, this planner should be moved out of robot_state
100 
101 public:
102  struct Percentage
103  {
104  // value must be in [0,1]
106  {
107  if (value < 0.0 || value > 1.0)
108  throw std::runtime_error("Percentage values must be between 0 and 1, inclusive");
109  }
110  operator double()
111  {
112  return value;
113  }
114  double operator*()
115  {
116  return value;
117  }
119  {
120  Percentage res(value * p.value);
121  return res;
122  }
123  double value;
124  };
125 
126  struct Distance
127  {
129  {
130  }
131  operator double()
132  {
133  return meters;
134  }
135  double operator*()
136  {
137  return meters;
138  }
140  {
141  Distance res(meters * p.value);
142  return res;
143  }
144  double meters;
145  };
146 
167  RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& path,
168  const LinkModel* link, const Eigen::Vector3d& translation, bool global_reference_frame,
169  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
173 
179  RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& path,
180  const LinkModel* link, const Eigen::Vector3d& direction, bool global_reference_frame, double distance,
181  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
185  {
186  return computeCartesianPath(start_state, group, path, link, distance * direction, global_reference_frame, max_step,
187  jump_threshold, validCallback, options, cost_function);
188  }
189 
198  RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& path,
199  const LinkModel* link, const Eigen::Isometry3d& target, bool global_reference_frame, const MaxEEFStep& max_step,
200  const JumpThreshold& jump_threshold,
204  const Eigen::Isometry3d& link_offset = Eigen::Isometry3d::Identity());
205 
213  RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& path,
214  const LinkModel* link, const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame,
215  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
219  const Eigen::Isometry3d& link_offset = Eigen::Isometry3d::Identity());
220 
231  static Percentage checkJointSpaceJump(const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& path,
232  const JumpThreshold& jump_threshold);
233 };
234 
241 std::optional<int> hasJointSpaceJump(const std::vector<moveit::core::RobotStatePtr>& waypoints,
242  const moveit::core::JointModelGroup& group,
243  const moveit::core::JumpThreshold& jump_threshold);
244 
245 } // end of namespace core
246 } // 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(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(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.h:72
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h: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.h: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.h:43
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
A set of options for the kinematics solver.
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)