moveit2
The MoveIt Motion Planning Framework for ROS 2.
cached_ik_kinematics_plugin-inl.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Rice University
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 the Rice University 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: Mark Moll */
36 
37 #include <chrono>
38 #include <cstdlib>
39 
41 {
42 template <class KinematicsPlugin>
44 {
45 }
46 
47 template <class KinematicsPlugin>
49 {
50 }
51 
52 template <class KinematicsPlugin>
53 void CachedIKKinematicsPlugin<KinematicsPlugin>::initCache(const std::string& robot_id, const std::string& group_name,
54  const std::string& cache_name)
55 {
56  IKCache::Options opts;
57  opts.max_cache_size = params_.max_cache_size;
58  opts.min_pose_distance = params_.min_pose_distance;
59  opts.min_joint_config_distance = params_.min_joint_config_distance;
60  opts.cached_ik_path = params_.cached_ik_path;
61 
62  cache_.initializeCache(robot_id, group_name, cache_name, KinematicsPlugin::getJointNames().size(), opts);
63 
64  // for debugging purposes:
65  // kdl_kinematics_plugin::KDLKinematicsPlugin fk;
66  // fk.initialize(robot_description, group_name, base_frame, tip_frame, search_discretization);
67  // cache_.verifyCache(fk);
68 }
69 
70 template <class KinematicsPlugin>
72  const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model, const std::string& group_name,
73  const std::string& base_frame, const std::vector<std::string>& tip_frames, double search_discretization)
74 {
75  // call initialize method of wrapped class
76  if (!KinematicsPlugin::initialize(node, robot_model, group_name, base_frame, tip_frames, search_discretization))
77  return false;
78 
79  std::string cache_name = base_frame;
80  std::accumulate(tip_frames.begin(), tip_frames.end(), cache_name);
81  CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.initializeCache(robot_model.getName(), group_name, cache_name,
82  KinematicsPlugin::getJointNames().size());
83  return true;
84 }
85 
86 template <class KinematicsPlugin>
87 bool CachedIKKinematicsPlugin<KinematicsPlugin>::getPositionIK(const geometry_msgs::msg::Pose& ik_pose,
88  const std::vector<double>& ik_seed_state,
89  std::vector<double>& solution,
90  moveit_msgs::msg::MoveItErrorCodes& error_code,
91  const KinematicsQueryOptions& options) const
92 {
93  Pose pose(ik_pose);
94  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
95  bool solution_found = KinematicsPlugin::getPositionIK(ik_pose, nearest.second, solution, error_code, options) ||
96  KinematicsPlugin::getPositionIK(ik_pose, ik_seed_state, solution, error_code, options);
97  if (solution_found)
98  cache_.updateCache(nearest, pose, solution);
99  return solution_found;
100 }
101 
102 template <class KinematicsPlugin>
103 bool CachedIKKinematicsPlugin<KinematicsPlugin>::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
104  const std::vector<double>& ik_seed_state,
105  double timeout, std::vector<double>& solution,
106  moveit_msgs::msg::MoveItErrorCodes& error_code,
107  const KinematicsQueryOptions& options) const
108 {
109  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
110  Pose pose(ik_pose);
111  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
112  bool solution_found =
113  KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution, error_code, options);
114  if (!solution_found)
115  {
116  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
117  solution_found =
118  KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), solution, error_code, options);
119  }
120  if (solution_found)
121  cache_.updateCache(nearest, pose, solution);
122  return solution_found;
123 }
124 
125 template <class KinematicsPlugin>
127  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
128  const std::vector<double>& consistency_limits, std::vector<double>& solution,
129  moveit_msgs::msg::MoveItErrorCodes& error_code, const KinematicsQueryOptions& options) const
130 {
131  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
132  Pose pose(ik_pose);
133  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
134  bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
135  solution, error_code, options);
136  if (!solution_found)
137  {
138  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
139  solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
140  solution, error_code, options);
141  }
142  if (solution_found)
143  cache_.updateCache(nearest, pose, solution);
144  return solution_found;
145 }
146 
147 template <class KinematicsPlugin>
148 bool CachedIKKinematicsPlugin<KinematicsPlugin>::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
149  const std::vector<double>& ik_seed_state,
150  double timeout, std::vector<double>& solution,
151  const IKCallbackFn& solution_callback,
152  moveit_msgs::msg::MoveItErrorCodes& error_code,
153  const KinematicsQueryOptions& options) const
154 {
155  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
156  Pose pose(ik_pose);
157  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
158  bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution,
159  solution_callback, error_code, options);
160  if (!solution_found)
161  {
162  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
163  solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), solution,
164  solution_callback, error_code, options);
165  }
166  if (solution_found)
167  cache_.updateCache(nearest, pose, solution);
168  return solution_found;
169 }
170 
171 template <class KinematicsPlugin>
173  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
174  const std::vector<double>& consistency_limits, std::vector<double>& solution, const IKCallbackFn& solution_callback,
175  moveit_msgs::msg::MoveItErrorCodes& error_code, const KinematicsQueryOptions& options) const
176 {
177  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
178  Pose pose(ik_pose);
179  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
180  bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
181  solution, solution_callback, error_code, options);
182  if (!solution_found)
183  {
184  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
185  solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
186  solution, solution_callback, error_code, options);
187  }
188  if (solution_found)
189  cache_.updateCache(nearest, pose, solution);
190  return solution_found;
191 }
192 
193 template <class KinematicsPlugin>
195  const std::vector<geometry_msgs::msg::Pose>& ik_poses, const std::vector<double>& ik_seed_state, double timeout,
196  const std::vector<double>& consistency_limits, std::vector<double>& solution, const IKCallbackFn& solution_callback,
197  moveit_msgs::msg::MoveItErrorCodes& error_code, const KinematicsQueryOptions& options,
198  const moveit::core::RobotState* context_state) const
199 {
200  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
201  std::vector<Pose> poses(ik_poses.size());
202  for (unsigned int i = 0; i < poses.size(); ++i)
203  poses[i] = Pose(ik_poses[i]);
204  const IKEntry& nearest = CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.getBestApproximateIKSolution(poses);
205  bool solution_found =
206  KinematicsPlugin::searchPositionIK(ik_poses, nearest.second, timeout, consistency_limits, solution,
207  solution_callback, error_code, options, context_state);
208  if (!solution_found)
209  {
210  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
211  solution_found =
212  KinematicsPlugin::searchPositionIK(ik_poses, ik_seed_state, diff.count(), consistency_limits, solution,
213  solution_callback, error_code, options, context_state);
214  }
215 
216  if (solution_found)
217  CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.updateCache(nearest, poses, solution);
218  return solution_found;
219 }
220 } // namespace cached_ik_kinematics_plugin
bool getPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
bool searchPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
bool searchPositionIK(const std::vector< geometry_msgs::msg::Pose > &ik_poses, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::msg::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions(), const moveit::core::RobotState *context_state=nullptr) const override
bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:76
const std::string & getName() const
Get the model name.
Definition: robot_model.h:85
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
A set of options for the kinematics solver.