moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
ik_cache.cpp
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 <numeric>
38#include <filesystem>
39#include <fstream>
40
43
45{
46namespace
47{
48rclcpp::Logger getLogger()
49{
50 return moveit::getLogger("moveit.core.dynamics_solver");
51}
52} // namespace
54{
55 // set distance function for nearest-neighbor queries
56 ik_nn_.setDistanceFunction([](const IKEntry* entry1, const IKEntry* entry2) {
57 double dist = 0.;
58 for (unsigned int i = 0; i < entry1->first.size(); ++i)
59 dist += entry1->first[i].distance(entry2->first[i]);
60 return dist;
61 });
62}
63
65{
66 if (!ik_cache_.empty())
67 saveCache();
68}
69
70void IKCache::initializeCache(const std::string& robot_id, const std::string& group_name, const std::string& cache_name,
71 const unsigned int num_joints, const Options& opts)
72{
73 // read ROS parameters
79 std::string cached_ik_path = opts.cached_ik_path;
80
81 // use mutex lock for rest of initialization
82 std::lock_guard<std::mutex> slock(lock_);
83 // determine cache file name
84 std::filesystem::path prefix(!cached_ik_path.empty() ? std::filesystem::path(cached_ik_path) :
85 std::filesystem::current_path());
86 // create cache directory if necessary
87 std::filesystem::create_directories(prefix);
88
89 cache_file_name_ = prefix / (robot_id + group_name + "_" + cache_name + "_" + std::to_string(max_cache_size_) + "_" +
90 std::to_string(min_pose_distance_) + "_" +
91 std::to_string(std::sqrt(min_config_distance2_)) + ".ikcache");
92
93 ik_cache_.clear();
94 ik_nn_.clear();
96 if (std::filesystem::exists(cache_file_name_))
97 {
98 // read cache
99 std::ifstream cache_file(cache_file_name_, std::ios_base::binary | std::ios_base::in);
100 cache_file.read(reinterpret_cast<char*>(&last_saved_cache_size_), sizeof(unsigned int));
101 unsigned int num_dofs;
102 cache_file.read(reinterpret_cast<char*>(&num_dofs), sizeof(unsigned int));
103 unsigned int num_tips;
104 cache_file.read(reinterpret_cast<char*>(&num_tips), sizeof(unsigned int));
105
106 RCLCPP_INFO(getLogger(), "Found %d IK solutions for a %d-dof system with %d end effectors in %s",
107 last_saved_cache_size_, num_dofs, num_tips, cache_file_name_.string().c_str());
108
109 unsigned int position_size = 3 * sizeof(tf2Scalar);
110 unsigned int orientation_size = 4 * sizeof(tf2Scalar);
111 unsigned int pose_size = position_size + orientation_size;
112 unsigned int config_size = num_dofs * sizeof(double);
113 unsigned int offset_conf = pose_size * num_tips;
114 unsigned int bufsize = offset_conf + config_size;
115 char* buffer = new char[bufsize];
116 IKEntry entry;
117 entry.first.resize(num_tips);
118 entry.second.resize(num_dofs);
120
121 for (unsigned i = 0; i < last_saved_cache_size_; ++i)
122 {
123 unsigned int j = 0;
124 cache_file.read(buffer, bufsize);
125 for (auto& pose : entry.first)
126 {
127 memcpy(&pose.position[0], buffer + j * pose_size, position_size);
128 memcpy(&pose.orientation[0], buffer + j * pose_size + position_size, orientation_size);
129 ++j;
130 }
131 memcpy(&entry.second[0], buffer + offset_conf, config_size);
132 ik_cache_.push_back(entry);
133 }
134 RCLCPP_INFO(getLogger(), "freeing buffer");
135 delete[] buffer;
136 RCLCPP_INFO(getLogger(), "freed buffer");
137 std::vector<IKEntry*> ik_entry_ptrs(last_saved_cache_size_);
138 for (unsigned int i = 0; i < last_saved_cache_size_; ++i)
139 ik_entry_ptrs[i] = &ik_cache_[i];
140 ik_nn_.add(ik_entry_ptrs);
141 }
142
143 num_joints_ = num_joints;
144
145 RCLCPP_INFO(getLogger(), "cache file %s initialized!", cache_file_name_.string().c_str());
146}
147
148double IKCache::configDistance2(const std::vector<double>& config1, const std::vector<double>& config2) const
149{
150 double dist = 0., diff;
151 for (unsigned int i = 0; i < config1.size(); ++i)
152 {
153 diff = config1[i] - config2[i];
154 dist += diff * diff;
155 }
156 return dist;
157}
158
160{
161 if (ik_cache_.empty())
162 {
163 static IKEntry dummy = std::make_pair(std::vector<Pose>(1, pose), std::vector<double>(num_joints_, 0.));
164 return dummy;
165 }
166 IKEntry query = std::make_pair(std::vector<Pose>(1, pose), std::vector<double>());
167 return *ik_nn_.nearest(&query);
168}
169
170const IKCache::IKEntry& IKCache::getBestApproximateIKSolution(const std::vector<Pose>& poses) const
171{
172 if (ik_cache_.empty())
173 {
174 static IKEntry dummy = std::make_pair(poses, std::vector<double>(num_joints_, 0.));
175 return dummy;
176 }
177 IKEntry query = std::make_pair(poses, std::vector<double>());
178 return *ik_nn_.nearest(&query);
179}
180
181void IKCache::updateCache(const IKEntry& nearest, const Pose& pose, const std::vector<double>& config) const
182{
183 if (ik_cache_.size() < ik_cache_.capacity() && (nearest.first[0].distance(pose) > min_pose_distance_ ||
184 configDistance2(nearest.second, config) > min_config_distance2_))
185 {
186 std::lock_guard<std::mutex> slock(lock_);
187 ik_cache_.emplace_back(std::vector<Pose>(1u, pose), config);
188 ik_nn_.add(&ik_cache_.back());
189 if (ik_cache_.size() >= last_saved_cache_size_ + 500u || ik_cache_.size() == max_cache_size_)
190 saveCache();
191 }
192}
193
194void IKCache::updateCache(const IKEntry& nearest, const std::vector<Pose>& poses,
195 const std::vector<double>& config) const
196{
197 if (ik_cache_.size() < ik_cache_.capacity())
198 {
199 bool add_to_cache = configDistance2(nearest.second, config) > min_config_distance2_;
200 if (!add_to_cache)
201 {
202 double dist = 0.;
203 for (unsigned int i = 0; i < poses.size(); ++i)
204 {
205 dist += nearest.first[i].distance(poses[i]);
206 if (dist > min_pose_distance_)
207 {
208 add_to_cache = true;
209 break;
210 }
211 }
212 }
213 if (add_to_cache)
214 {
215 std::lock_guard<std::mutex> slock(lock_);
216 ik_cache_.emplace_back(poses, config);
217 ik_nn_.add(&ik_cache_.back());
218 if (ik_cache_.size() >= last_saved_cache_size_ + 500u || ik_cache_.size() == max_cache_size_)
219 saveCache();
220 }
221 }
222}
223
225{
226 if (cache_file_name_.empty())
227 RCLCPP_ERROR(getLogger(), "can't save cache before initialization");
228
229 RCLCPP_INFO(getLogger(), "writing %ld IK solutions to %s", ik_cache_.size(), cache_file_name_.string().c_str());
230
231 std::ofstream cache_file(cache_file_name_, std::ios_base::binary | std::ios_base::out);
232 unsigned int position_size = 3 * sizeof(tf2Scalar);
233 unsigned int orientation_size = 4 * sizeof(tf2Scalar);
234 unsigned int pose_size = position_size + orientation_size;
235 unsigned int num_tips = ik_cache_[0].first.size();
236 unsigned int config_size = ik_cache_[0].second.size() * sizeof(double);
237 unsigned int offset_conf = num_tips * pose_size;
238 unsigned int bufsize = offset_conf + config_size;
239 char* buffer = new char[bufsize];
240
241 // write number of IK entries and size of each configuration first
243 cache_file.write(reinterpret_cast<char*>(&last_saved_cache_size_), sizeof(unsigned int));
244 unsigned int sz = ik_cache_[0].second.size();
245 cache_file.write(reinterpret_cast<char*>(&sz), sizeof(unsigned int));
246 cache_file.write(reinterpret_cast<char*>(&num_tips), sizeof(unsigned int));
247 for (const auto& entry : ik_cache_)
248 {
249 for (unsigned int i = 0; i < num_tips; ++i)
250 {
251 memcpy(buffer + i * pose_size, &entry.first[i].position[0], position_size);
252 memcpy(buffer + i * pose_size + position_size, &entry.first[i].orientation[0], orientation_size);
253 }
254 memcpy(buffer + offset_conf, &entry.second[0], config_size);
255 cache_file.write(buffer, bufsize);
256 }
257 delete[] buffer;
258}
259
261{
262 const std::vector<std::string>& tip_names(fk.getTipFrames());
263 std::vector<geometry_msgs::msg::Pose> poses(tip_names.size());
264 double error, max_error = 0.;
265
266 for (const auto& entry : ik_cache_)
267 {
268 fk.getPositionFK(tip_names, entry.second, poses);
269 error = 0.;
270 for (unsigned int i = 0; i < poses.size(); ++i)
271 error += entry.first[i].distance(poses[i]);
272 if (!poses.empty())
273 error /= static_cast<double>(poses.size());
274 if (error > max_error)
275 max_error = error;
276 if (error > 1e-4)
277 RCLCPP_ERROR(getLogger(), "Cache entry is invalid, error = %g", error);
278 }
279 RCLCPP_INFO(getLogger(), "Max. error in cache entries is %g", max_error);
280}
281
282IKCache::Pose::Pose(const geometry_msgs::msg::Pose& pose)
283{
284 position.setX(pose.position.x);
285 position.setY(pose.position.y);
286 position.setZ(pose.position.z);
287 orientation = tf2::Quaternion(pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w);
288}
289
290double IKCache::Pose::distance(const Pose& pose) const
291{
292 return (position - pose.position).length() + (orientation.angleShortestPath(pose.orientation));
293}
294
295IKCacheMap::IKCacheMap(const std::string& robot_description, const std::string& group_name, unsigned int num_joints)
296 : robot_description_(robot_description), group_name_(group_name), num_joints_(num_joints)
297{
298}
299
301{
302 for (auto& cache : *this)
303 delete cache.second;
304}
305
306const IKCache::IKEntry& IKCacheMap::getBestApproximateIKSolution(const std::vector<std::string>& fixed,
307 const std::vector<std::string>& active,
308 const std::vector<Pose>& poses) const
309{
310 auto key(getKey(fixed, active));
311 auto it = find(key);
312 if (it != end())
313 {
314 return it->second->getBestApproximateIKSolution(poses);
315 }
316 else
317 {
318 static IKEntry dummy = std::make_pair(poses, std::vector<double>(num_joints_, 0.));
319 return dummy;
320 }
321}
322
323void IKCacheMap::updateCache(const IKEntry& nearest, const std::vector<std::string>& fixed,
324 const std::vector<std::string>& active, const std::vector<Pose>& poses,
325 const std::vector<double>& config)
326{
327 auto key(getKey(fixed, active));
328 auto it = find(key);
329 if (it != end())
330 {
331 it->second->updateCache(nearest, poses, config);
332 }
333 else
334 {
335 value_type val = std::make_pair(key, nullptr);
336 auto it = insert(val).first;
337 it->second = new IKCache;
339 }
340}
341
342std::string IKCacheMap::getKey(const std::vector<std::string>& fixed, const std::vector<std::string>& active) const
343{
344 std::string key;
345 std::accumulate(fixed.begin(), fixed.end(), key);
346 key += '_';
347 std::accumulate(active.begin(), active.end(), key);
348 return key;
349}
350} // namespace cached_ik_kinematics_plugin
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
IKCacheMap(const std::string &robot_description, const std::string &group_name, unsigned int num_joints)
Definition ik_cache.cpp:295
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
void setDistanceFunction(const typename NearestNeighbors< _T >::DistanceFunction &distFun) override
void add(const _T &data) override
Add an element to the datastructure.
void clear() override
Clear the datastructure.
_T nearest(const _T &data) const override
Get the nearest neighbor of a point.
Specific implementation of kinematics using KDL. This version supports any kinematic chain,...
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::msg::Pose > &poses) const override
Given a set of joint angles and a set of links, compute their pose.
virtual const std::vector< std::string > & getTipFrames() const
Return the names of the tip frames of the kinematic tree on which the solver is operating....
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