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 #include <tf2/LinearMath/Quaternion.h>
44 #include <tf2/LinearMath/Vector3.h>
45 #include <mutex>
46 #include <unordered_map>
47 #include <utility>
48 #include <filesystem>
49 #include <cached_ik_kinematics_parameters.hpp>
50 
52 {
53 static const rclcpp::Logger LOGGER =
54  rclcpp::get_logger("moveit_cached_ik_kinematics_plugin.cached_ik_kinematics_plugin");
55 
57 class IKCache
58 {
59 public:
60  struct Options
61  {
63  {
64  }
65  unsigned int max_cache_size;
68  std::string cached_ik_path;
69  };
70 
78  struct Pose
79  {
80  Pose() = default;
81  Pose(const geometry_msgs::msg::Pose& pose);
82  tf2::Vector3 position;
83  tf2::Quaternion orientation;
85  double distance(const Pose& pose) const;
86  };
87 
93  using IKEntry = std::pair<std::vector<Pose>, std::vector<double>>;
94 
95  IKCache();
96  ~IKCache();
97  IKCache(const IKCache&) = delete;
98 
100  const IKEntry& getBestApproximateIKSolution(const Pose& pose) const;
102  const IKEntry& getBestApproximateIKSolution(const std::vector<Pose>& poses) const;
104  void initializeCache(const std::string& robot_id, const std::string& group_name, const std::string& cache_name,
105  const unsigned int num_joints, const Options& opts = Options());
110  void updateCache(const IKEntry& nearest, const Pose& pose, const std::vector<double>& config) const;
115  void updateCache(const IKEntry& nearest, const std::vector<Pose>& poses, const std::vector<double>& config) const;
118 
119 protected:
121  double configDistance2(const std::vector<double>& config1, const std::vector<double>& config2) const;
123  void saveCache() const;
124 
126  unsigned int num_joints_;
127 
133  unsigned int max_cache_size_;
135  std::filesystem::path cache_file_name_;
136 
143  mutable std::vector<IKEntry> ik_cache_;
147  mutable unsigned int last_saved_cache_size_{ 0 };
149  mutable std::mutex lock_;
150 };
151 
153 class IKCacheMap : public std::unordered_map<std::string, IKCache*>
154 {
155 public:
158 
159  IKCacheMap(const std::string& robot_description, const std::string& group_name, unsigned int num_joints);
160  ~IKCacheMap();
165  const IKEntry& getBestApproximateIKSolution(const std::vector<std::string>& fixed,
166  const std::vector<std::string>& active,
167  const std::vector<Pose>& poses) const;
172  void updateCache(const IKEntry& nearest, const std::vector<std::string>& fixed,
173  const std::vector<std::string>& active, const std::vector<Pose>& poses,
174  const std::vector<double>& config);
175 
176 protected:
177  std::string getKey(const std::vector<std::string>& fixed, const std::vector<std::string>& active) const;
178  std::string robot_description_;
179  std::string group_name_;
180  unsigned int num_joints_;
181 };
182 
183 // Helper class to enable/disable initialize() methods with new/old API
184 // HasRobotModelApi<T>::value provides a true/false constexpr depending on KinematicsPlugin offers the new Api
185 // This uses SFINAE magic: https://jguegant.github.io/blogs/tech/sfinae-introduction.html
186 template <typename KinematicsPlugin, typename = bool>
187 struct HasRobotModelApi : std::false_type
188 {
189 };
190 
191 template <typename KinematicsPlugin>
192 struct HasRobotModelApi<KinematicsPlugin, decltype(std::declval<KinematicsPlugin&>().initialize(
193  std::declval<const rclcpp::Node::SharedPtr&>(),
194  std::declval<const moveit::core::RobotModel&>(), std::string(),
195  std::string(), std::vector<std::string>(), 0.0))> : std::true_type
196 {
197 };
198 
199 template <typename KinematicsPlugin, typename = bool>
200 struct HasRobotDescApi : std::false_type
201 {
202 };
203 
204 template <typename KinematicsPlugin>
205 struct HasRobotDescApi<KinematicsPlugin,
206  decltype(std::declval<KinematicsPlugin&>().KinematicsPlugin::initialize(
207  std::string(), std::string(), std::string(), std::vector<std::string>(), 0.0))>
208  : std::true_type
209 {
210 };
211 
213 template <class KinematicsPlugin>
214 class CachedIKKinematicsPlugin : public KinematicsPlugin
215 {
216 public:
221 
223 
224  ~CachedIKKinematicsPlugin() override;
225 
226  // virtual methods that need to be wrapped:
227 
228  bool initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
229  const std::string& group_name, const std::string& base_frame,
230  const std::vector<std::string>& tip_frames, double search_discretization) override
231  {
232  node_ = node;
233 
234  std::string kinematics_param_prefix = "robot_description_kinematics." + group_name;
235  param_listener_ = std::make_shared<cached_ik_kinematics::ParamListener>(node, kinematics_param_prefix);
236  params_ = param_listener_->get_params();
237 
238  return initializeImpl(node, robot_model, group_name, base_frame, tip_frames, search_discretization);
239  }
240 
241  bool getPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
242  std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
243  const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
244 
245  bool searchPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
246  double timeout, std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
247  const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
248 
249  bool searchPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
250  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
251  moveit_msgs::msg::MoveItErrorCodes& error_code,
252  const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
253 
254  bool searchPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
255  double timeout, std::vector<double>& solution, const IKCallbackFn& solution_callback,
256  moveit_msgs::msg::MoveItErrorCodes& error_code,
257  const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
258 
259  bool searchPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
260  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
261  const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
262  const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
263 
264 private:
265  rclcpp::Node::SharedPtr node_;
266  std::shared_ptr<cached_ik_kinematics::ParamListener> param_listener_;
267  cached_ik_kinematics::Params params_;
268 
269  IKCache cache_;
270 
271  void initCache(const std::string& robot_id, const std::string& group_name, const std::string& cache_name);
272 
273  /* Using templates and SFINAE magic, we can selectively enable/disable methods depending on
274  availability of API in wrapped KinematicsPlugin class.
275  However, as templates and virtual functions cannot be combined, we need helpers initializeImpl(). */
276  template <class T = KinematicsPlugin>
277  typename std::enable_if<HasRobotModelApi<T>::value, bool>::type
278  initializeImpl(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
279  const std::string& group_name, const std::string& base_frame,
280  const std::vector<std::string>& tip_frames, double search_discretization)
281  {
282  if (tip_frames.size() != 1)
283  {
284  RCLCPP_ERROR(LOGGER, "This solver does not support multiple tip frames");
285  return false;
286  }
287 
288  // call initialize method of wrapped class
289  if (!KinematicsPlugin::initialize(node, robot_model, group_name, base_frame, tip_frames, search_discretization))
290  return false;
291  initCache(robot_model.getName(), group_name, base_frame + tip_frames[0]);
292  return true;
293  }
294 
295  template <class T = KinematicsPlugin>
296  typename std::enable_if<!HasRobotModelApi<T>::value, bool>::type
297  initializeImpl(const rclcpp::Node::SharedPtr& /*unused*/, const moveit::core::RobotModel& /*unused*/,
298  const std::string& /*unused*/, const std::string& /*unused*/,
299  const std::vector<std::string>& /*unused*/, double /*unused*/)
300  {
301  return false; // API not supported
302  }
303 
304  template <class T = KinematicsPlugin>
305  typename std::enable_if<HasRobotDescApi<T>::value, bool>::type
306  initializeImpl(const std::string& robot_description, const std::string& group_name, const std::string& base_frame,
307  const std::string& tip_frame, double search_discretization)
308  {
309  // call initialize method of wrapped class
310  if (!KinematicsPlugin::initialize(robot_description, group_name, base_frame, tip_frame, search_discretization))
311  return false;
312  initCache(robot_description, group_name, base_frame + tip_frame);
313  return true;
314  }
315 
316  template <class T = KinematicsPlugin>
317  typename std::enable_if<!HasRobotDescApi<T>::value, bool>::type
318  initializeImpl(const std::string& /*unused*/, const std::string& /*unused*/, const std::string& /*unused*/,
319  const std::string& /*unused*/, double /*unused*/)
320  {
321  return false; // API not supported
322  }
323 };
324 
336 template <class KinematicsPlugin>
338 {
339 public:
344 
345  bool initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
346  const std::string& group_name, const std::string& base_frame,
347  const std::vector<std::string>& tip_frames, double search_discretization) override;
348 
349  bool searchPositionIK(const std::vector<geometry_msgs::msg::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
350  double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
351  const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
353  const moveit::core::RobotState* context_state = nullptr) const override;
354 };
355 } // namespace cached_ik_kinematics_plugin
356 
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:334
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:315
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.