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  int max_cache_size; // rosparam can't handle unsigned int
58  kinematics::KinematicsBase::lookupParam(node_, "max_cache_size", max_cache_size,
59  static_cast<int>(opts.max_cache_size));
60  opts.max_cache_size = max_cache_size;
61  kinematics::KinematicsBase::lookupParam(node_, "min_pose_distance", opts.min_pose_distance, 1.0);
62  kinematics::KinematicsBase::lookupParam(node_, "min_joint_config_distance", opts.min_joint_config_distance, 1.0);
63  kinematics::KinematicsBase::lookupParam<std::string>(node_, "cached_ik_path", opts.cached_ik_path, "");
64 
65  cache_.initializeCache(robot_id, group_name, cache_name, KinematicsPlugin::getJointNames().size(), opts);
66 
67  // for debugging purposes:
68  // kdl_kinematics_plugin::KDLKinematicsPlugin fk;
69  // fk.initialize(robot_description, group_name, base_frame, tip_frame, search_discretization);
70  // cache_.verifyCache(fk);
71 }
72 
73 template <class KinematicsPlugin>
75  const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model, const std::string& group_name,
76  const std::string& base_frame, const std::vector<std::string>& tip_frames, double search_discretization)
77 {
78  // call initialize method of wrapped class
79  if (!KinematicsPlugin::initialize(node, robot_model, group_name, base_frame, tip_frames, search_discretization))
80  return false;
81 
82  std::string cache_name = base_frame;
83  std::accumulate(tip_frames.begin(), tip_frames.end(), cache_name);
84  CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.initializeCache(robot_model.getName(), group_name, cache_name,
85  KinematicsPlugin::getJointNames().size());
86  return true;
87 }
88 
89 template <class KinematicsPlugin>
90 bool CachedIKKinematicsPlugin<KinematicsPlugin>::getPositionIK(const geometry_msgs::msg::Pose& ik_pose,
91  const std::vector<double>& ik_seed_state,
92  std::vector<double>& solution,
93  moveit_msgs::msg::MoveItErrorCodes& error_code,
94  const KinematicsQueryOptions& options) const
95 {
96  Pose pose(ik_pose);
97  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
98  bool solution_found = KinematicsPlugin::getPositionIK(ik_pose, nearest.second, solution, error_code, options) ||
99  KinematicsPlugin::getPositionIK(ik_pose, ik_seed_state, solution, error_code, options);
100  if (solution_found)
101  cache_.updateCache(nearest, pose, solution);
102  return solution_found;
103 }
104 
105 template <class KinematicsPlugin>
106 bool CachedIKKinematicsPlugin<KinematicsPlugin>::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
107  const std::vector<double>& ik_seed_state,
108  double timeout, std::vector<double>& solution,
109  moveit_msgs::msg::MoveItErrorCodes& error_code,
110  const KinematicsQueryOptions& options) const
111 {
112  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
113  Pose pose(ik_pose);
114  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
115  bool solution_found =
116  KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution, error_code, options);
117  if (!solution_found)
118  {
119  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
120  solution_found =
121  KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), solution, error_code, options);
122  }
123  if (solution_found)
124  cache_.updateCache(nearest, pose, solution);
125  return solution_found;
126 }
127 
128 template <class KinematicsPlugin>
130  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
131  const std::vector<double>& consistency_limits, std::vector<double>& solution,
132  moveit_msgs::msg::MoveItErrorCodes& error_code, const KinematicsQueryOptions& options) const
133 {
134  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
135  Pose pose(ik_pose);
136  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
137  bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
138  solution, error_code, options);
139  if (!solution_found)
140  {
141  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
142  solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
143  solution, error_code, options);
144  }
145  if (solution_found)
146  cache_.updateCache(nearest, pose, solution);
147  return solution_found;
148 }
149 
150 template <class KinematicsPlugin>
151 bool CachedIKKinematicsPlugin<KinematicsPlugin>::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
152  const std::vector<double>& ik_seed_state,
153  double timeout, std::vector<double>& solution,
154  const IKCallbackFn& solution_callback,
155  moveit_msgs::msg::MoveItErrorCodes& error_code,
156  const KinematicsQueryOptions& options) const
157 {
158  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
159  Pose pose(ik_pose);
160  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
161  bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution,
162  solution_callback, error_code, options);
163  if (!solution_found)
164  {
165  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
166  solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), solution,
167  solution_callback, error_code, options);
168  }
169  if (solution_found)
170  cache_.updateCache(nearest, pose, solution);
171  return solution_found;
172 }
173 
174 template <class KinematicsPlugin>
176  const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
177  const std::vector<double>& consistency_limits, std::vector<double>& solution, const IKCallbackFn& solution_callback,
178  moveit_msgs::msg::MoveItErrorCodes& error_code, const KinematicsQueryOptions& options) const
179 {
180  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
181  Pose pose(ik_pose);
182  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
183  bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
184  solution, solution_callback, error_code, options);
185  if (!solution_found)
186  {
187  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
188  solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
189  solution, solution_callback, error_code, options);
190  }
191  if (solution_found)
192  cache_.updateCache(nearest, pose, solution);
193  return solution_found;
194 }
195 
196 template <class KinematicsPlugin>
198  const std::vector<geometry_msgs::msg::Pose>& ik_poses, const std::vector<double>& ik_seed_state, double timeout,
199  const std::vector<double>& consistency_limits, std::vector<double>& solution, const IKCallbackFn& solution_callback,
200  moveit_msgs::msg::MoveItErrorCodes& error_code, const KinematicsQueryOptions& options,
201  const moveit::core::RobotState* context_state) const
202 {
203  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
204  std::vector<Pose> poses(ik_poses.size());
205  for (unsigned int i = 0; i < poses.size(); ++i)
206  poses[i] = Pose(ik_poses[i]);
207  const IKEntry& nearest = CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.getBestApproximateIKSolution(poses);
208  bool solution_found =
209  KinematicsPlugin::searchPositionIK(ik_poses, nearest.second, timeout, consistency_limits, solution,
210  solution_callback, error_code, options, context_state);
211  if (!solution_found)
212  {
213  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
214  solution_found =
215  KinematicsPlugin::searchPositionIK(ik_poses, ik_seed_state, diff.count(), consistency_limits, solution,
216  solution_callback, error_code, options, context_state);
217  }
218 
219  if (solution_found)
220  CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.updateCache(nearest, poses, solution);
221  return solution_found;
222 }
223 } // 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
bool lookupParam(const rclcpp::Node::SharedPtr &node, const std::string &param, T &val, const T &default_val) const
Enables kinematics plugins access to parameters that are defined for the private namespace and inside...
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.