moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
cached_ik_kinematics_plugin-inl.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
39#include <chrono>
40#include <cstdlib>
41
43{
44template <class KinematicsPlugin>
48
49template <class KinematicsPlugin>
53
54template <class KinematicsPlugin>
55void CachedIKKinematicsPlugin<KinematicsPlugin>::initCache(const std::string& robot_id, const std::string& group_name,
56 const std::string& cache_name)
57{
59 opts.max_cache_size = params_.max_cache_size;
60 opts.min_pose_distance = params_.min_pose_distance;
61 opts.min_joint_config_distance = params_.min_joint_config_distance;
62 opts.cached_ik_path = params_.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
72template <class KinematicsPlugin>
74 const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModel& robot_model, const std::string& group_name,
75 const std::string& base_frame, const std::vector<std::string>& tip_frames, double search_discretization)
76{
77 // call initialize method of wrapped class
78 if (!KinematicsPlugin::initialize(node, robot_model, group_name, base_frame, tip_frames, search_discretization))
79 return false;
80
81 std::string cache_name = base_frame;
82 std::accumulate(tip_frames.begin(), tip_frames.end(), cache_name);
83 CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.initializeCache(robot_model.getName(), group_name, cache_name,
84 KinematicsPlugin::getJointNames().size());
85 return true;
86}
87
88template <class KinematicsPlugin>
89bool CachedIKKinematicsPlugin<KinematicsPlugin>::getPositionIK(const geometry_msgs::msg::Pose& ik_pose,
90 const std::vector<double>& ik_seed_state,
91 std::vector<double>& solution,
92 moveit_msgs::msg::MoveItErrorCodes& error_code,
93 const KinematicsQueryOptions& options) const
94{
95 Pose pose(ik_pose);
96 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
97 bool solution_found = KinematicsPlugin::getPositionIK(ik_pose, nearest.second, solution, error_code, options) ||
98 KinematicsPlugin::getPositionIK(ik_pose, ik_seed_state, solution, error_code, options);
99 if (solution_found)
100 cache_.updateCache(nearest, pose, solution);
101 return solution_found;
102}
103
104template <class KinematicsPlugin>
105bool CachedIKKinematicsPlugin<KinematicsPlugin>::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
106 const std::vector<double>& ik_seed_state,
107 double timeout, std::vector<double>& solution,
108 moveit_msgs::msg::MoveItErrorCodes& error_code,
109 const KinematicsQueryOptions& options) const
110{
111 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
112 Pose pose(ik_pose);
113 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
114 bool solution_found =
115 KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution, error_code, options);
116 if (!solution_found)
117 {
118 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
119 solution_found =
120 KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), solution, error_code, options);
121 }
122 if (solution_found)
123 cache_.updateCache(nearest, pose, solution);
124 return solution_found;
125}
126
127template <class KinematicsPlugin>
129 const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
130 const std::vector<double>& consistency_limits, std::vector<double>& solution,
131 moveit_msgs::msg::MoveItErrorCodes& error_code, const KinematicsQueryOptions& options) const
132{
133 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
134 Pose pose(ik_pose);
135 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
136 bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
137 solution, error_code, options);
138 if (!solution_found)
139 {
140 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
141 solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
142 solution, error_code, options);
143 }
144 if (solution_found)
145 cache_.updateCache(nearest, pose, solution);
146 return solution_found;
147}
148
149template <class KinematicsPlugin>
150bool CachedIKKinematicsPlugin<KinematicsPlugin>::searchPositionIK(const geometry_msgs::msg::Pose& ik_pose,
151 const std::vector<double>& ik_seed_state,
152 double timeout, std::vector<double>& solution,
153 const IKCallbackFn& solution_callback,
154 moveit_msgs::msg::MoveItErrorCodes& error_code,
155 const KinematicsQueryOptions& options) const
156{
157 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
158 Pose pose(ik_pose);
159 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
160 bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, solution,
161 solution_callback, error_code, options);
162 if (!solution_found)
163 {
164 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
165 solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), solution,
166 solution_callback, error_code, options);
167 }
168 if (solution_found)
169 cache_.updateCache(nearest, pose, solution);
170 return solution_found;
171}
172
173template <class KinematicsPlugin>
175 const geometry_msgs::msg::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
176 const std::vector<double>& consistency_limits, std::vector<double>& solution, const IKCallbackFn& solution_callback,
177 moveit_msgs::msg::MoveItErrorCodes& error_code, const KinematicsQueryOptions& options) const
178{
179 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
180 Pose pose(ik_pose);
181 const IKEntry& nearest = cache_.getBestApproximateIKSolution(pose);
182 bool solution_found = KinematicsPlugin::searchPositionIK(ik_pose, nearest.second, timeout, consistency_limits,
183 solution, solution_callback, error_code, options);
184 if (!solution_found)
185 {
186 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
187 solution_found = KinematicsPlugin::searchPositionIK(ik_pose, ik_seed_state, diff.count(), consistency_limits,
188 solution, solution_callback, error_code, options);
189 }
190 if (solution_found)
191 cache_.updateCache(nearest, pose, solution);
192 return solution_found;
193}
194
195template <class KinematicsPlugin>
197 const std::vector<geometry_msgs::msg::Pose>& ik_poses, const std::vector<double>& ik_seed_state, double timeout,
198 const std::vector<double>& consistency_limits, std::vector<double>& solution, const IKCallbackFn& solution_callback,
199 moveit_msgs::msg::MoveItErrorCodes& error_code, const KinematicsQueryOptions& options,
200 const moveit::core::RobotState* context_state) const
201{
202 std::chrono::time_point<std::chrono::system_clock> start(std::chrono::system_clock::now());
203 std::vector<Pose> poses(ik_poses.size());
204 for (unsigned int i = 0; i < poses.size(); ++i)
205 poses[i] = Pose(ik_poses[i]);
206 const IKEntry& nearest = CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.getBestApproximateIKSolution(poses);
207 bool solution_found =
208 KinematicsPlugin::searchPositionIK(ik_poses, nearest.second, timeout, consistency_limits, solution,
209 solution_callback, error_code, options, context_state);
210 if (!solution_found)
211 {
212 std::chrono::duration<double> diff = std::chrono::system_clock::now() - start;
213 solution_found =
214 KinematicsPlugin::searchPositionIK(ik_poses, ik_seed_state, diff.count(), consistency_limits, solution,
215 solution_callback, error_code, options, context_state);
216 }
217
218 if (solution_found)
219 CachedIKKinematicsPlugin<KinematicsPlugin>::cache_.updateCache(nearest, poses, solution);
220 return solution_found;
221}
222} // 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
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.
A set of options for the kinematics solver.