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("max_cache_size", max_cache_size, static_cast<int>(opts.max_cache_size));
59  opts.max_cache_size = max_cache_size;
60  kinematics::KinematicsBase::lookupParam("min_pose_distance", opts.min_pose_distance, 1.0);
61  kinematics::KinematicsBase::lookupParam("min_joint_config_distance", opts.min_joint_config_distance, 1.0);
62  kinematics::KinematicsBase::lookupParam<std::string>("cached_ik_path", opts.cached_ik_path, "");
63 
64  cache_.initializeCache(robot_id, group_name, cache_name, KinematicsPlugin::getJointNames().size(), opts);
65 
66  // for debugging purposes:
67  // kdl_kinematics_plugin::KDLKinematicsPlugin fk;
68  // fk.initialize(robot_description, group_name, base_frame, tip_frame, search_discretization);
69  // cache_.verifyCache(fk);
70 }
71 
72 template <class KinematicsPlugin>
74  const std::string& group_name,
75  const std::string& base_frame,
76  const std::vector<std::string>& tip_frames,
77  double search_discretization)
78 {
79  // call initialize method of wrapped class
80  if (!KinematicsPlugin::initialize(robot_model, group_name, base_frame, tip_frames, search_discretization))
81  return false;
82 
83  std::string cache_name = base_frame;
84  std::accumulate(tip_frames.begin(), tip_frames.end(), cache_name);
85  CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.initializeCache(robot_model.getName(), group_name, cache_name,
86  KinematicsPlugin::getJointNames().size());
87  return true;
88 }
89 
90 template <class KinematicsPlugin>
91 bool CachedMultiTipIKKinematicsPlugin<KinematicsPlugin>::initialize(const std::string& robot_description,
92  const std::string& group_name,
93  const std::string& base_frame,
94  const std::vector<std::string>& tip_frames,
95  double search_discretization)
96 {
97  // call initialize method of wrapped class
98  if (!KinematicsPlugin::initialize(robot_description, group_name, base_frame, tip_frames, search_discretization))
99  return false;
100 
101  std::string cache_name = base_frame;
102  std::accumulate(tip_frames.begin(), tip_frames.end(), cache_name);
103  CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.initializeCache(robot_description, group_name, cache_name,
104  KinematicsPlugin::getJointNames().size());
105  return true;
106 }
107 
108 template <class KinematicsPlugin>
109 bool CachedIKKinematicsPlugin<KinematicsPlugin>::getPositionIK(const geometry_msgs::Pose& ik_pose,
110  const std::vector<double>& ik_seed_state,
111  std::vector<double>& solution,
112  moveit_msgs::MoveItErrorCodes& error_code,
113  const KinematicsQueryOptions& options) const
114 {
115  Pose pose(ik_pose);
116  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
117  bool solution_found = KinematicsPlugin::getPositionIK(ik_pose, nearest.second, solution, error_code, options) ||
118  KinematicsPlugin::getPositionIK(ik_pose, ik_seed_state, solution, error_code, options);
119  if (solution_found)
120  cache_.updateCache(nearest, pose, solution);
121  return solution_found;
122 }
123 
124 template <class KinematicsPlugin>
125 bool CachedIKKinematicsPlugin<KinematicsPlugin>::searchPositionIK(const geometry_msgs::Pose& ik_pose,
126  const std::vector<double>& ik_seed_state,
127  double timeout, std::vector<double>& solution,
128  moveit_msgs::MoveItErrorCodes& error_code,
129  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 =
135  KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution, error_code, options);
136  if (!solution_found)
137  {
138  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
139  solution_found =
140  KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), 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>
149  const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
150  const std::vector<double>& consistency_limits, std::vector<double>& solution,
151  moveit_msgs::MoveItErrorCodes& error_code, const KinematicsQueryOptions& options) const
152 {
153  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
154  Pose pose(ik_pose);
155  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
156  bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
157  solution, error_code, options);
158  if (!solution_found)
159  {
160  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
161  solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
162  solution, error_code, options);
163  }
164  if (solution_found)
165  cache_.updateCache(nearest, pose, solution);
166  return solution_found;
167 }
168 
169 template <class KinematicsPlugin>
170 bool CachedIKKinematicsPlugin<KinematicsPlugin>::searchPositionIK(const geometry_msgs::Pose& ik_pose,
171  const std::vector<double>& ik_seed_state,
172  double timeout, std::vector<double>& solution,
173  const IKCallbackFn& solution_callback,
174  moveit_msgs::MoveItErrorCodes& error_code,
175  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, solution,
181  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(), solution,
186  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 geometry_msgs::Pose& ik_pose, 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::MoveItErrorCodes& error_code, const KinematicsQueryOptions& options) const
198 {
199  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
200  Pose pose(ik_pose);
201  const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
202  bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
203  solution, solution_callback, error_code, options);
204  if (!solution_found)
205  {
206  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
207  solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
208  solution, solution_callback, error_code, options);
209  }
210  if (solution_found)
211  cache_.updateCache(nearest, pose, solution);
212  return solution_found;
213 }
214 
215 template <class KinematicsPlugin>
217  const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state, double timeout,
218  const std::vector<double>& consistency_limits, std::vector<double>& solution, const IKCallbackFn& solution_callback,
219  moveit_msgs::MoveItErrorCodes& error_code, const KinematicsQueryOptions& options,
220  const moveit::core::RobotState* context_state) const
221 {
222  std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
223  std::vector<Pose> poses(ik_poses.size());
224  for (unsigned int i = 0; i < poses.size(); ++i)
225  poses[i] = Pose(ik_poses[i]);
226  const IKEntry& nearest = CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.getBestApproximateIKSolution(poses);
227  bool solution_found =
228  KinematicsPlugin::searchPositionIK(ik_poses, nearest.second, timeout, consistency_limits, solution,
229  solution_callback, error_code, options, context_state);
230  if (!solution_found)
231  {
232  std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
233  solution_found =
234  KinematicsPlugin::searchPositionIK(ik_poses, ik_seed_state, diff.count(), consistency_limits, solution,
235  solution_callback, error_code, options, context_state);
236  }
237 
238  if (solution_found)
239  CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.updateCache(nearest, poses, solution);
240  return solution_found;
241 }
242 } // namespace cached_ik_kinematics_plugin
kinematics::KinematicsBase::lookupParam
bool lookupParam(const std::string &param, T &val, const T &default_val) const
cached_ik_kinematics_plugin
Definition: cached_ik_kinematics_plugin-inl.h:40
cached_ik_kinematics_plugin::IKCache::Pose
class to represent end effector pose
Definition: cached_ik_kinematics_plugin.h:138
cached_ik_kinematics_plugin::IKCache::Options::min_pose_distance
double min_pose_distance
Definition: cached_ik_kinematics_plugin.h:158
moveit::core::RobotModel
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin::initCache
void initCache(const std::string &robot_id, const std::string &group_name, const std::string &cache_name)
Definition: cached_ik_kinematics_plugin-inl.h:85
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin::IKEntry
IKCache::IKEntry IKEntry
Definition: cached_ik_kinematics_plugin.h:245
cached_ik_kinematics_plugin::IKCache::Options::max_cache_size
unsigned int max_cache_size
Definition: cached_ik_kinematics_plugin.h:157
moveit::core::RobotState
cached_ik_kinematics_plugin::CachedMultiTipIKKinematicsPlugin::searchPositionIK
bool searchPositionIK(const std::vector< geometry_msgs::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::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions(), const moveit::core::RobotState *context_state=nullptr) const override
Definition: cached_ik_kinematics_plugin-inl.h:248
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin::searchPositionIK
bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
Definition: cached_ik_kinematics_plugin-inl.h:157
cached_ik_kinematics_plugin::IKCache::Options::cached_ik_path
std::string cached_ik_path
Definition: cached_ik_kinematics_plugin.h:160
cached_ik_kinematics_plugin::IKCache::Options
Definition: cached_ik_kinematics_plugin.h:120
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin::CachedIKKinematicsPlugin
CachedIKKinematicsPlugin()
Definition: cached_ik_kinematics_plugin-inl.h:75
moveit::core::RobotModel::getName
const std::string & getName() const
start
ROSCPP_DECL void start()
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin
Definition: cached_ik_kinematics_plugin.h:241
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin::~CachedIKKinematicsPlugin
~CachedIKKinematicsPlugin() override
Definition: cached_ik_kinematics_plugin-inl.h:80
kinematics::KinematicsQueryOptions
cached_ik_kinematics_plugin::IKCache::Options::min_joint_config_distance
double min_joint_config_distance
Definition: cached_ik_kinematics_plugin.h:159
cached_ik_kinematics_plugin::CachedIKKinematicsPlugin::getPositionIK
bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const KinematicsQueryOptions &options=KinematicsQueryOptions()) const override
Definition: cached_ik_kinematics_plugin-inl.h:141
cached_ik_kinematics_plugin::CachedMultiTipIKKinematicsPlugin::initialize
bool initialize(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: cached_ik_kinematics_plugin-inl.h:105


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:15