moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
cached_ik_kinematics_plugin.hpp
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#include <cached_ik_kinematics_parameters.hpp>
60
62{
63
66{
67public:
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
127protected:
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
161class IKCacheMap : public std::unordered_map<std::string, IKCache*>
162{
163public:
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
184protected:
185 std::string getKey(const std::vector<std::string>& fixed, const std::vector<std::string>& active) const;
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
194template <typename KinematicsPlugin, typename = bool>
195struct HasRobotModelApi : std::false_type
196{
197};
198
199template <typename KinematicsPlugin>
200struct 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
207template <typename KinematicsPlugin, typename = bool>
208struct HasRobotDescApi : std::false_type
209{
210};
211
212template <typename KinematicsPlugin>
213struct 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
221template <class KinematicsPlugin>
222class CachedIKKinematicsPlugin : public KinematicsPlugin
223{
224public:
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
242 std::string kinematics_param_prefix = "robot_description_kinematics." + group_name;
243 param_listener_ = std::make_shared<cached_ik_kinematics::ParamListener>(node, kinematics_param_prefix);
244 params_ = param_listener_->get_params();
245
246 return initializeImpl(node, robot_model, group_name, base_frame, tip_frames, search_discretization);
247 }
248
249 bool getPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
250 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
251 const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
252
253 bool searchPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
254 double timeout, std::vector<double>& solution, 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, const std::vector<double>& consistency_limits, std::vector<double>& solution,
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, std::vector<double>& solution, const IKCallbackFn& solution_callback,
264 moveit_msgs::msg::MoveItErrorCodes& error_code,
265 const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
266
267 bool searchPositionIK(const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state,
268 double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
269 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
270 const KinematicsQueryOptions& options = KinematicsQueryOptions()) const override;
271
272private:
273 rclcpp::Node::SharedPtr node_;
274 std::shared_ptr<cached_ik_kinematics::ParamListener> param_listener_;
275 cached_ik_kinematics::Params params_;
276
277 IKCache cache_;
278
279 void initCache(const std::string& robot_id, const std::string& group_name, const std::string& cache_name);
280
281 /* Using templates and SFINAE magic, we can selectively enable/disable methods depending on
282 availability of API in wrapped KinematicsPlugin class.
283 However, as templates and virtual functions cannot be combined, we need helpers initializeImpl(). */
284 template <class T = KinematicsPlugin>
285 typename std::enable_if<HasRobotModelApi<T>::value, bool>::type
286 initializeImpl(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
287 const std::string& group_name, const std::string& base_frame,
288 const std::vector<std::string>& tip_frames, double search_discretization)
289 {
290 if (tip_frames.size() != 1)
291 {
292 RCLCPP_ERROR(moveit::getLogger("moveit.core.cached_ik_kinematics_plugin"),
293 "This solver does not support multiple tip frames");
294 return false;
295 }
296
297 // call initialize method of wrapped class
298 if (!KinematicsPlugin::initialize(node, robot_model, group_name, base_frame, tip_frames, search_discretization))
299 return false;
300 initCache(robot_model.getName(), group_name, base_frame + tip_frames[0]);
301 return true;
302 }
303
304 template <class T = KinematicsPlugin>
305 typename std::enable_if<!HasRobotModelApi<T>::value, bool>::type
306 initializeImpl(const rclcpp::Node::SharedPtr& /*unused*/, const moveit::core::RobotModel& /*unused*/,
307 const std::string& /*unused*/, const std::string& /*unused*/,
308 const std::vector<std::string>& /*unused*/, double /*unused*/)
309 {
310 return false; // API not supported
311 }
312
313 template <class T = KinematicsPlugin>
314 typename std::enable_if<HasRobotDescApi<T>::value, bool>::type
315 initializeImpl(const std::string& robot_description, const std::string& group_name, const std::string& base_frame,
316 const std::string& tip_frame, double search_discretization)
317 {
318 // call initialize method of wrapped class
319 if (!KinematicsPlugin::initialize(robot_description, group_name, base_frame, tip_frame, search_discretization))
320 return false;
321 initCache(robot_description, group_name, base_frame + tip_frame);
322 return true;
323 }
324
325 template <class T = KinematicsPlugin>
326 typename std::enable_if<!HasRobotDescApi<T>::value, bool>::type
327 initializeImpl(const std::string& /*unused*/, const std::string& /*unused*/, const std::string& /*unused*/,
328 const std::string& /*unused*/, double /*unused*/)
329 {
330 return false; // API not supported
331 }
332};
333
345template <class KinematicsPlugin>
347{
348public:
353
354 bool initialize(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model,
355 const std::string& group_name, const std::string& base_frame,
356 const std::vector<std::string>& tip_frames, double search_discretization) override;
357
358 bool searchPositionIK(const std::vector<geometry_msgs::msg::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
359 double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
360 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
362 const moveit::core::RobotState* context_state = nullptr) const override;
363};
364} // namespace cached_ik_kinematics_plugin
365
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:306
std::string getKey(const std::vector< std::string > &fixed, const std::vector< std::string > &active) const
Definition ik_cache.cpp:342
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:323
A cache of inverse kinematic solutions.
const IKEntry & getBestApproximateIKSolution(const Pose &pose) const
Definition ik_cache.cpp:159
std::pair< std::vector< Pose >, std::vector< double > > IKEntry
void verifyCache(kdl_kinematics_plugin::KDLKinematicsPlugin &fk) const
Definition ik_cache.cpp:260
double configDistance2(const std::vector< double > &config1, const std::vector< double > &config2) const
Definition ik_cache.cpp:148
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:70
void updateCache(const IKEntry &nearest, const Pose &pose, const std::vector< double > &config) const
Definition ik_cache.cpp:181
IKCache(const IKCache &)=delete
Geometric Near-neighbor Access Tree (GNAT), a data structure for nearest neighbor search.
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...
const std::string & getName() const
Get the model name.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
double distance(const Pose &pose) const
Definition ik_cache.cpp:290
A set of options for the kinematics solver.