moveit2
The MoveIt Motion Planning Framework for ROS 2.
cached_ik_kinematics_plugin.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 #pragma once
38 
43 // TODO: Remove conditional includes when released to all active distros.
44 #if __has_include(<tf2/LinearMath/Quaternion.hpp>)
45 #include <tf2/LinearMath/Quaternion.hpp>
46 #else
47 #include <tf2/LinearMath/Quaternion.h>
48 #endif
49 #if __has_include(<tf2/LinearMath/Vector3.hpp>)
50 #include <tf2/LinearMath/Vector3.hpp>
51 #else
52 #include <tf2/LinearMath/Vector3.h>
53 #endif
54 #include <mutex>
55 #include <unordered_map>
56 #include <utility>
57 #include <filesystem>
58 
60 {
61 static const rclcpp::Logger LOGGER =
62  rclcpp::get_logger("moveit_cached_ik_kinematics_plugin.cached_ik_kinematics_plugin");
63 
65 class IKCache
66 {
67 public:
68  struct Options
69  {
71  {
72  }
73  unsigned int max_cache_size;
76  std::string cached_ik_path;
77  };
78 
86  struct Pose
87  {
88  Pose() = default;
89  Pose(const geometry_msgs::msg::Pose& pose);
90  tf2::Vector3 position;
91  tf2::Quaternion orientation;
93  double distance(const Pose& pose) const;
94  };
95 
101  using IKEntry = std::pair<std::vector<Pose>, std::vector<double>>;
102 
103  IKCache();
104  ~IKCache();
105  IKCache(const IKCache&) = delete;
106 
108  const IKEntry& getBestApproximateIKSolution(const Pose& pose) const;
110  const IKEntry& getBestApproximateIKSolution(const std::vector<Pose>& poses) const;
112  void initializeCache(const std::string& robot_id, const std::string& group_name, const std::string& cache_name,
113  const unsigned int num_joints, const Options& opts = Options());
118  void updateCache(const IKEntry& nearest, const Pose& pose, const std::vector<double>& config) const;
123  void updateCache(const IKEntry& nearest, const std::vector<Pose>& poses, const std::vector<double>& config) const;
126 
127 protected:
129  double configDistance2(const std::vector<double>& config1, const std::vector<double>& config2) const;
131  void saveCache() const;
132 
134  unsigned int num_joints_;
135 
141  unsigned int max_cache_size_;
143  std::filesystem::path cache_file_name_;
144 
151  mutable std::vector<IKEntry> ik_cache_;
155  mutable unsigned int last_saved_cache_size_{ 0 };
157  mutable std::mutex lock_;
158 };
159 
161 class IKCacheMap : public std::unordered_map<std::string, IKCache*>
162 {
163 public:
166 
167  IKCacheMap(const std::string& robot_description, const std::string& group_name, unsigned int num_joints);
168  ~IKCacheMap();
173  const IKEntry& getBestApproximateIKSolution(const std::vector<std::string>& fixed,
174  const std::vector<std::string>& active,
175  const std::vector<Pose>& poses) const;
180  void updateCache(const IKEntry& nearest, const std::vector<std::string>& fixed,
181  const std::vector<std::string>& active, const std::vector<Pose>& poses,
182  const std::vector<double>& config);
183 
184 protected:
185  std::string getKey(const std::vector<std::string>& fixed, const std::vector<std::string>& active) const;
186  std::string robot_description_;
187  std::string group_name_;
188  unsigned int num_joints_;
189 };
190 
191 // Helper class to enable/disable initialize() methods with new/old API
192 // HasRobotModelApi<T>::value provides a true/false constexpr depending on KinematicsPlugin offers the new Api
193 // This uses SFINAE magic: https://jguegant.github.io/blogs/tech/sfinae-introduction.html
194 template <typename KinematicsPlugin, typename = bool>
195 struct HasRobotModelApi : std::false_type
196 {
197 };
198 
199 template <typename KinematicsPlugin>
200 struct HasRobotModelApi<KinematicsPlugin, decltype(std::declval<KinematicsPlugin&>().initialize(
201  std::declval<const rclcpp::Node::SharedPtr&>(),
202  std::declval<const moveit::core::RobotModel&>(), std::string(),
203  std::string(), std::vector<std::string>(), 0.0))> : std::true_type
204 {
205 };
206 
207 template <typename KinematicsPlugin, typename = bool>
208 struct HasRobotDescApi : std::false_type
209 {
210 };
211 
212 template <typename KinematicsPlugin>
213 struct HasRobotDescApi<KinematicsPlugin,
214  decltype(std::declval<KinematicsPlugin&>().KinematicsPlugin::initialize(
215  std::string(), std::string(), std::string(), std::vector<std::string>(), 0.0))>
216  : std::true_type
217 {
218 };
219 
221 template <class KinematicsPlugin>
222 class CachedIKKinematicsPlugin : public KinematicsPlugin
223 {
224 public:
229 
231 
232  ~CachedIKKinematicsPlugin() override;
233 
234  // virtual methods that need to be wrapped:
235 
236  bool initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
237  const std::string& group_name, const std::string& base_frame,
238  const std::vector<std::string>& tip_frames, double search_discretization) override
239  {
240  node_ = node;
241  return initializeImpl(node, robot_model, group_name, base_frame, tip_frames, search_discretization);
242  }
243 
244  bool getPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
245  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
246  const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
247 
248  bool searchPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
249  double timeout, std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
250  const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
251 
252  bool searchPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
253  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
254  moveit_msgs::msg::MoveItErrorCodes& error_code,
255  const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
256 
257  bool searchPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
258  double timeout, std::vector<double>& solution, const IKCallbackFn& solution_callback,
259  moveit_msgs::msg::MoveItErrorCodes& error_code,
260  const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
261 
262  bool searchPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
263  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
264  const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
265  const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
266 
267 private:
268  rclcpp::Node::SharedPtr node_;
269 
270  IKCache cache_;
271 
272  void initCache(const std::string& robot_id, const std::string& group_name, const std::string& cache_name);
273 
274  /* Using templates and SFINAE magic, we can selectively enable/disable methods depending on
275  availability of API in wrapped KinematicsPlugin class.
276  However, as templates and virtual functions cannot be combined, we need helpers initializeImpl(). */
277  template <class T = KinematicsPlugin>
278  typename std::enable_if<HasRobotModelApi<T>::value, bool>::type
279  initializeImpl(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
280  const std::string& group_name, const std::string& base_frame,
281  const std::vector<std::string>& tip_frames, double search_discretization)
282  {
283  if (tip_frames.size() != 1)
284  {
285  RCLCPP_ERROR(LOGGER, "This solver does not support multiple tip frames");
286  return false;
287  }
288 
289  // call initialize method of wrapped class
290  if (!KinematicsPlugin::initialize(node, robot_model, group_name, base_frame, tip_frames, search_discretization))
291  return false;
292  initCache(robot_model.getName(), group_name, base_frame + tip_frames[0]);
293  return true;
294  }
295 
296  template <class T = KinematicsPlugin>
297  typename std::enable_if<!HasRobotModelApi<T>::value, bool>::type
298  initializeImpl(const rclcpp::Node::SharedPtr& /*unused*/, const moveit::core::RobotModel& /*unused*/,
299  const std::string& /*unused*/, const std::string& /*unused*/,
300  const std::vector<std::string>& /*unused*/, double /*unused*/)
301  {
302  return false; // API not supported
303  }
304 
305  template <class T = KinematicsPlugin>
306  typename std::enable_if<HasRobotDescApi<T>::value, bool>::type
307  initializeImpl(const std::string& robot_description, const std::string& group_name, const std::string& base_frame,
308  const std::string& tip_frame, double search_discretization)
309  {
310  // call initialize method of wrapped class
311  if (!KinematicsPlugin::initialize(robot_description, group_name, base_frame, tip_frame, search_discretization))
312  return false;
313  initCache(robot_description, group_name, base_frame + tip_frame);
314  return true;
315  }
316 
317  template <class T = KinematicsPlugin>
318  typename std::enable_if<!HasRobotDescApi<T>::value, bool>::type
319  initializeImpl(const std::string& /*unused*/, const std::string& /*unused*/, const std::string& /*unused*/,
320  const std::string& /*unused*/, double /*unused*/)
321  {
322  return false; // API not supported
323  }
324 };
325 
337 template <class KinematicsPlugin>
339 {
340 public:
345 
346  bool initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
347  const std::string& group_name, const std::string& base_frame,
348  const std::vector<std::string>& tip_frames, double search_discretization) override;
349 
350  bool searchPositionIK(const std::vector<geometry_msgs::msg::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
351  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
352  const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
354  const moveit::core::RobotState* context_state = nullptr) const override;
355 };
356 } // namespace cached_ik_kinematics_plugin
357 
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 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 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
const IKEntry & getBestApproximateIKSolution(const std::vector< std::string > &fixed, const std::vector< std::string > &active, const std::vector< Pose > &poses) const
Definition: ik_cache.cpp:298
std::string getKey(const std::vector< std::string > &fixed, const std::vector< std::string > &active) const
Definition: ik_cache.cpp:330
void updateCache(const IKEntry &nearest, const std::vector< std::string > &fixed, const std::vector< std::string > &active, const std::vector< Pose > &poses, const std::vector< double > &config)
Definition: ik_cache.cpp:313
IKCacheMap(const std::string &robot_description, const std::string &group_name, unsigned int num_joints)
Definition: ik_cache.cpp:287
A cache of inverse kinematic solutions.
const IKEntry & getBestApproximateIKSolution(const Pose &pose) const
Definition: ik_cache.cpp:151
std::pair< std::vector< Pose >, std::vector< double > > IKEntry
void verifyCache(kdl_kinematics_plugin::KDLKinematicsPlugin &fk) const
Definition: ik_cache.cpp:252
NearestNeighborsGNAT< IKEntry * > ik_nn_
double configDistance2(const std::vector< double > &config1, const std::vector< double > &config2) const
Definition: ik_cache.cpp:140
void initializeCache(const std::string &robot_id, const std::string &group_name, const std::string &cache_name, const unsigned int num_joints, const Options &opts=Options())
Definition: ik_cache.cpp:62
void updateCache(const IKEntry &nearest, const Pose &pose, const std::vector< double > &config) const
Definition: ik_cache.cpp:173
IKCache(const IKCache &)=delete
Specific implementation of kinematics using KDL. This version supports any kinematic chain,...
std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
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
double distance(const Pose &pose) const
Definition: ik_cache.cpp:282
A set of options for the kinematics solver.