moveit2
The MoveIt Motion Planning Framework for ROS 2.
kinematics_plugin_loader.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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: Ioan Sucan, Dave Coleman */
36 
39 #include <pluginlib/class_loader.hpp>
40 #include <rclcpp/logger.hpp>
41 #include <rclcpp/logging.hpp>
42 #include <rclcpp/parameter.hpp>
43 #include <rclcpp/parameter_value.hpp>
44 #include <sstream>
45 #include <vector>
46 #include <map>
47 #include <memory>
48 #include <mutex>
49 #include <moveit/utils/logger.hpp>
50 
52 {
54 {
55 public:
62  KinematicsLoaderImpl(const rclcpp::Node::SharedPtr& node, const std::string& robot_description,
63  const std::map<std::string, std::string>& possible_kinematics_solvers,
64  const std::map<std::string, double>& search_res, const rclcpp::Logger& logger)
65  : node_(node)
66  , robot_description_(robot_description)
67  , possible_kinematics_solvers_(possible_kinematics_solvers)
68  , search_res_(search_res)
69  , logger_(logger)
70  {
71  try
72  {
73  kinematics_loader_ =
74  std::make_shared<pluginlib::ClassLoader<kinematics::KinematicsBase>>("moveit_core", "kinematics::"
75  "KinematicsBase");
76  }
77  catch (pluginlib::PluginlibException& e)
78  {
79  RCLCPP_ERROR(logger_, "Unable to construct kinematics loader. Error: %s", e.what());
80  }
81  }
82 
88  std::vector<std::string> chooseTipFrames(const moveit::core::JointModelGroup* jmg)
89  {
90  std::vector<std::string> tips;
91  // get the last link in the chain
92  RCLCPP_DEBUG(logger_,
93  "Choosing tip frame of kinematic solver for group %s"
94  "based on last link in chain",
95  jmg->getName().c_str());
96 
97  tips.push_back(jmg->getLinkModels().back()->getName());
98 
99  // Error check
100  if (tips.empty())
101  {
102  RCLCPP_ERROR(logger_, "Error choosing kinematic solver tip frame(s).");
103  }
104 
105  // Debug tip choices
106  std::stringstream tip_debug;
107  tip_debug << "Planning group '" << jmg->getName() << "' has tip(s): ";
108  for (const auto& tip : tips)
109  tip_debug << tip << ", ";
110  RCLCPP_DEBUG_STREAM(logger_, tip_debug.str());
111 
112  return tips;
113  }
114 
115  kinematics::KinematicsBasePtr allocKinematicsSolver(const moveit::core::JointModelGroup* jmg)
116  {
117  kinematics::KinematicsBasePtr result;
118  if (!kinematics_loader_)
119  {
120  RCLCPP_ERROR(logger_, "Invalid kinematics loader.");
121  return result;
122  }
123  if (!jmg)
124  {
125  RCLCPP_ERROR(logger_, "Specified group is nullptr. Cannot allocate kinematics solver.");
126  return result;
127  }
128  const std::vector<const moveit::core::LinkModel*>& links = jmg->getLinkModels();
129  if (links.empty())
130  {
131  RCLCPP_ERROR(logger_, "No links specified for group '%s'. Cannot allocate kinematics solver.",
132  jmg->getName().c_str());
133  return result;
134  }
135 
136  RCLCPP_DEBUG(logger_, "Trying to allocate kinematics solver for group '%s'", jmg->getName().c_str());
137 
138  const std::string& base = links.front()->getParentJointModel()->getParentLinkModel() ?
139  links.front()->getParentJointModel()->getParentLinkModel()->getName() :
140  jmg->getParentModel().getModelFrame();
141 
142  // just to be sure, do not call the same pluginlib instance allocation function in parallel
143  std::scoped_lock slock(lock_);
144  for (const auto& [group, solver] : possible_kinematics_solvers_)
145  {
146  // Don't bother trying to load a solver for the wrong group
147  if (group != jmg->getName())
148  {
149  continue;
150  }
151  try
152  {
153  result = kinematics_loader_->createUniqueInstance(solver);
154  if (result)
155  {
156  // choose the tip of the IK solver
157  const std::vector<std::string> tips = chooseTipFrames(jmg);
158 
159  // choose search resolution
160  double search_res = search_res_.find(jmg->getName())->second; // we know this exists, by construction
161 
162  if (!result->initialize(node_, jmg->getParentModel(), jmg->getName(),
163  (base.empty() || base[0] != '/') ? base : base.substr(1), tips, search_res))
164  {
165  RCLCPP_ERROR(logger_, "Kinematics solver of type '%s' could not be initialized for group '%s'",
166  solver.c_str(), jmg->getName().c_str());
167  result.reset();
168  continue;
169  }
170 
171  result->setDefaultTimeout(jmg->getDefaultIKTimeout());
172  RCLCPP_DEBUG(logger_,
173  "Successfully allocated and initialized a kinematics solver of type '%s' with search "
174  "resolution %lf for group '%s' at address %p",
175  solver.c_str(), search_res, jmg->getName().c_str(), result.get());
176  break;
177  }
178  }
179  catch (pluginlib::PluginlibException& e)
180  {
181  RCLCPP_ERROR(logger_, "The kinematics plugin (%s) failed to load. Error: %s", solver.c_str(), e.what());
182  }
183  }
184 
185  if (!result)
186  {
187  RCLCPP_DEBUG(logger_, "No usable kinematics solver was found for this group.\n"
188  "Did you load kinematics.yaml into your node's namespace?");
189  }
190  return result;
191  }
192 
193  // cache solver between two consecutive calls
194  // first call in RobotModelLoader::loadKinematicsSolvers() is just to check suitability for jmg
195  // second call in JointModelGroup::setSolverAllocators() is to actually retrieve the instance for use
196  kinematics::KinematicsBasePtr allocKinematicsSolverWithCache(const moveit::core::JointModelGroup* jmg)
197  {
198  std::scoped_lock slock(cache_lock_);
199  kinematics::KinematicsBasePtr& cached = instances_[jmg];
200  if (cached.unique())
201  return std::move(cached); // pass on unique instance
202 
203  // create a new instance and store in instances_
204  cached = allocKinematicsSolver(jmg);
205  return cached;
206  }
207 
208  void status() const
209  {
210  for (const auto& [group, solver] : possible_kinematics_solvers_)
211  {
212  RCLCPP_INFO(logger_, "Solver for group '%s': '%s' (search resolution = %lf)", group.c_str(), solver.c_str(),
213  search_res_.at(group));
214  }
215  }
216 
217 private:
218  const rclcpp::Node::SharedPtr node_;
219  std::string robot_description_;
220  std::map<std::string, std::string> possible_kinematics_solvers_;
221  std::map<std::string, double> search_res_;
222  std::shared_ptr<pluginlib::ClassLoader<kinematics::KinematicsBase>> kinematics_loader_;
223  std::map<const moveit::core::JointModelGroup*, kinematics::KinematicsBasePtr> instances_;
224  std::mutex lock_;
225  std::mutex cache_lock_;
226  rclcpp::Logger logger_;
227 };
228 
230 {
231  if (loader_)
232  {
233  loader_->status();
234  }
235  else
236  {
237  RCLCPP_INFO(logger_, "Loader function was never required");
238  }
239 }
240 
242 {
243  if (!loader_)
244  {
245  RCLCPP_DEBUG(logger_, "Configuring kinematics solvers");
246  groups_.clear();
247 
248  std::map<std::string, std::string> possible_kinematics_solvers;
249  std::map<std::string, double> search_res;
250  std::map<std::string, std::vector<std::string>> iksolver_to_tip_links;
251 
252  if (srdf_model)
253  {
254  const std::vector<srdf::Model::Group>& known_groups = srdf_model->getGroups();
255 
256  RCLCPP_DEBUG(logger_, "Loading kinematics parameters...");
257  // read the list of plugin names for possible kinematics solvers
258  for (const srdf::Model::Group& known_group : known_groups)
259  {
260  std::string kinematics_param_prefix = robot_description_ + "_kinematics." + known_group.name_;
261  group_param_listener_.try_emplace(known_group.name_,
262  std::make_shared<kinematics::ParamListener>(node_, kinematics_param_prefix));
263  group_params_.try_emplace(known_group.name_, group_param_listener_.at(known_group.name_)->get_params());
264 
265  std::string kinematics_solver_param_name = kinematics_param_prefix + ".kinematics_solver";
266  const auto kinematics_solver = group_params_.at(known_group.name_).kinematics_solver;
267 
268  if (kinematics_solver.empty())
269  {
270  RCLCPP_DEBUG(logger_, "No kinematics solver specified for group '%s'.", known_group.name_.c_str());
271  continue;
272  }
273 
274  // Only push back a group if it has a kinematics solver.
275  groups_.push_back(known_group.name_);
276 
277  possible_kinematics_solvers[known_group.name_] = kinematics_solver;
278  RCLCPP_DEBUG(logger_, "Found kinematics solver '%s' for group '%s'.", kinematics_solver.c_str(),
279  known_group.name_.c_str());
280 
281  std::string kinematics_solver_res_param_name = kinematics_param_prefix + ".kinematics_solver_search_resolution";
282  const auto kinematics_solver_search_resolution =
283  group_params_.at(known_group.name_).kinematics_solver_search_resolution;
284  search_res[known_group.name_] = kinematics_solver_search_resolution;
285  RCLCPP_DEBUG(logger_, "Found param %s : %f", kinematics_solver_res_param_name.c_str(),
286  kinematics_solver_search_resolution);
287 
288  std::string kinematics_solver_timeout_param_name = kinematics_param_prefix + ".kinematics_solver_timeout";
289  const auto kinematics_solver_timeout = group_params_.at(known_group.name_).kinematics_solver_timeout;
290  ik_timeout_[known_group.name_] = kinematics_solver_timeout;
291  RCLCPP_DEBUG(logger_, "Found param %s : %f", kinematics_solver_timeout_param_name.c_str(),
292  kinematics_solver_timeout);
293  }
294  }
295 
296  loader_ = std::make_shared<KinematicsLoaderImpl>(node_, robot_description_, possible_kinematics_solvers, search_res,
297  logger_);
298  }
299 
300  return [&loader = *loader_](const moveit::core::JointModelGroup* jmg) {
301  return loader.allocKinematicsSolverWithCache(jmg);
302  };
303 }
304 } // namespace kinematics_plugin_loader
std::vector< std::string > chooseTipFrames(const moveit::core::JointModelGroup *jmg)
Helper function to decide which, and how many, tip frames a planning group has.
kinematics::KinematicsBasePtr allocKinematicsSolverWithCache(const moveit::core::JointModelGroup *jmg)
KinematicsLoaderImpl(const rclcpp::Node::SharedPtr &node, const std::string &robot_description, const std::map< std::string, std::string > &possible_kinematics_solvers, const std::map< std::string, double > &search_res, const rclcpp::Logger &logger)
Pimpl Implementation of KinematicsLoader.
kinematics::KinematicsBasePtr allocKinematicsSolver(const moveit::core::JointModelGroup *jmg)
moveit::core::SolverAllocatorFn getLoaderFunction(const srdf::ModelSharedPtr &srdf_model)
Get a function pointer that allocates and initializes a kinematics solver. If not previously called,...
double getDefaultIKTimeout() const
Get the default IK timeout.
const std::string & getName() const
Get the name of the joint group.
const std::vector< const LinkModel * > & getLinkModels() const
Get the links that are part of this joint group.
const RobotModel & getParentModel() const
Get the kinematic model this group is part of.
const std::string & getModelFrame() const
Get the frame in which the transforms for this model are computed (when using a RobotState)....
Definition: robot_model.hpp:94
std::function< kinematics::KinematicsBasePtr(const JointModelGroup *)> SolverAllocatorFn
Function type that allocates a kinematics solver for a particular group.