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 {
53 {
54  double factor;
55  double revolute; // Radians
56  double prismatic; // Meters
57 
58  explicit JumpThreshold() : factor(0.0), revolute(0.0), prismatic(0.0)
59  {
60  }
61 
62  explicit JumpThreshold(double jt_factor) : JumpThreshold()
63  {
64  factor = jt_factor;
65  }
66 
67  explicit JumpThreshold(double jt_revolute, double jt_prismatic) : JumpThreshold()
68  {
69  revolute = jt_revolute; // Radians
70  prismatic = jt_prismatic; // Meters
71  }
72 };
73 
79 struct MaxEEFStep
80 {
82  {
83  }
84 
85  MaxEEFStep(double step_size) : translation(step_size), rotation(3.5 * step_size) // 0.035 rad = 2 deg
86  {
87  }
88 
89  double translation; // Meters
90  double rotation; // Radians
91 };
92 
94 {
95  // TODO(mlautman): Eventually, this planner should be moved out of robot_state
96 
97 public:
98  struct Percentage
99  {
100  // value must be in [0,1]
102  {
103  if (value < 0.0 || value > 1.0)
104  throw std::runtime_error("Percentage values must be between 0 and 1, inclusive");
105  }
106  operator double()
107  {
108  return value;
109  }
110  double operator*()
111  {
112  return value;
113  }
115  {
116  Percentage res(value * p.value);
117  return res;
118  }
119  double value;
120  };
121 
122  struct Distance
123  {
125  {
126  }
127  operator double()
128  {
129  return meters;
130  }
131  double operator*()
132  {
133  return meters;
134  }
136  {
137  Distance res(meters * p.value);
138  return res;
139  }
140  double meters;
141  };
142 
174  RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& traj,
175  const LinkModel* link, const Eigen::Vector3d& translation, bool global_reference_frame,
176  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
180 
186  RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& traj,
187  const LinkModel* link, const Eigen::Vector3d& direction, bool global_reference_frame, double distance,
188  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
192  {
193  return computeCartesianPath(start_state, group, traj, link, distance * direction, global_reference_frame, max_step,
194  jump_threshold, validCallback, options, cost_function);
195  }
196 
205  RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& traj,
206  const LinkModel* link, const Eigen::Isometry3d& target, bool global_reference_frame, const MaxEEFStep& max_step,
207  const JumpThreshold& jump_threshold,
211  const Eigen::Isometry3d& link_offset = Eigen::Isometry3d::Identity());
212 
220  RobotState* start_state, const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& traj,
221  const LinkModel* link, const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame,
222  const MaxEEFStep& max_step, const JumpThreshold& jump_threshold,
226  const Eigen::Isometry3d& link_offset = Eigen::Isometry3d::Identity());
227 
245  static Percentage checkJointSpaceJump(const JointModelGroup* group, std::vector<std::shared_ptr<RobotState>>& traj,
246  const JumpThreshold& jump_threshold);
247 
261  std::vector<std::shared_ptr<RobotState>>& traj,
262  double jump_threshold_factor);
263 
279  std::vector<std::shared_ptr<RobotState>>& traj,
280  double revolute_jump_threshold, double prismatic_jump_threshold);
281 };
282 
283 } // end of namespace core
284 } // end of namespace moveit
std::function< double(const geometry_msgs::msg::Pose &, const moveit::core::RobotState &, moveit::core::JointModelGroup const *, const std::vector< double > &)> IKCostFn
Signature for a cost function used to evaluate IK solutions.
static Distance computeCartesianPath(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 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,...
static Percentage computeCartesianPath(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 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 Percentage computeCartesianPath(RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, 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 Percentage checkAbsoluteJointSpaceJump(const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, double revolute_jump_threshold, double prismatic_jump_threshold)
Tests for absolute joint space jumps of the trajectory traj.
static Distance computeCartesianPath(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 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 checkRelativeJointSpaceJump(const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, double jump_threshold_factor)
Tests for relative joint space jumps of the trajectory traj.
static Percentage checkJointSpaceJump(const JointModelGroup *group, std::vector< std::shared_ptr< RobotState >> &traj, const JumpThreshold &jump_threshold)
Tests joint space jumps of a trajectory.
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
Main namespace for MoveIt.
Definition: exceptions.h:43
p
Definition: pick.py:62
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
A set of options for the kinematics solver.
Struct for containing jump_threshold.
JumpThreshold(double jt_revolute, double jt_prismatic)
Struct for containing max_step for computeCartesianPath.
MaxEEFStep(double translation, double rotation)