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 
40 #include <boost/thread/mutex.hpp>
41 #include <sstream>
42 #include <vector>
43 #include <map>
44 #include <memory>
45 #include <ros/ros.h>
47 
49 {
50 static const std::string LOGNAME = "kinematics_plugin_loader";
51 
52 class KinematicsPluginLoader::KinematicsLoaderImpl
53 {
54 public:
62  KinematicsLoaderImpl(const std::string& robot_description,
63  const std::map<std::string, std::vector<std::string>>& possible_kinematics_solvers,
64  const std::map<std::string, std::vector<double>>& search_res,
65  const std::map<std::string, std::vector<std::string>>& iksolver_to_tip_links)
66  : robot_description_(robot_description)
67  , possible_kinematics_solvers_(possible_kinematics_solvers)
68  , search_res_(search_res)
69  , iksolver_to_tip_links_(iksolver_to_tip_links)
70  {
71  try
72  {
74  std::make_shared<pluginlib::ClassLoader<kinematics::KinematicsBase>>("moveit_core", "kinematics::"
75  "KinematicsBase");
76  }
78  {
79  ROS_ERROR_NAMED(LOGNAME, "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  std::map<std::string, std::vector<std::string>>::const_iterator ik_it = iksolver_to_tip_links_.find(jmg->getName());
92 
93  // Check if tips were loaded onto the rosparam server previously
94  if (ik_it != iksolver_to_tip_links_.end())
95  {
96  // the tip is being chosen based on a corresponding rosparam ik link
97  ROS_DEBUG_STREAM_NAMED("kinematics_plugin_loader", "Choosing tip frame of kinematic solver for group "
98  << jmg->getName()
99  << " based on values in rosparam server.");
100  tips = ik_it->second;
101  }
102  else
103  {
104  // get the last link in the chain
105  ROS_DEBUG_STREAM_NAMED("kinematics_plugin_loader", "Choosing tip frame of kinematic solver for group "
106  << jmg->getName() << " based on last link in chain");
107 
108  tips.push_back(jmg->getLinkModels().back()->getName());
109  }
110 
111  // Error check
112  if (tips.empty())
113  {
114  ROS_ERROR_STREAM_NAMED("kinematics_plugin_loader", "Error choosing kinematic solver tip frame(s).");
115  }
116 
117  // Debug tip choices
118  std::stringstream tip_debug;
119  tip_debug << "Planning group '" << jmg->getName() << "' has tip(s): ";
120  for (const std::string& tip : tips)
121  tip_debug << tip << ", ";
122  ROS_DEBUG_STREAM_NAMED("kinematics_plugin_loader", tip_debug.str());
123 
124  return tips;
125  }
126 
127  kinematics::KinematicsBasePtr allocKinematicsSolver(const moveit::core::JointModelGroup* jmg)
128  {
129  kinematics::KinematicsBasePtr result;
130  if (!kinematics_loader_)
131  {
132  ROS_ERROR_NAMED(LOGNAME, "Invalid kinematics loader.");
133  return result;
134  }
135  if (!jmg)
136  {
137  ROS_ERROR_NAMED(LOGNAME, "Specified group is NULL. Cannot allocate kinematics solver.");
138  return result;
139  }
140  const std::vector<const moveit::core::LinkModel*>& links = jmg->getLinkModels();
141  if (links.empty())
142  {
143  ROS_ERROR_NAMED(LOGNAME, "No links specified for group '%s'. Cannot allocate kinematics solver.",
144  jmg->getName().c_str());
145  return result;
146  }
147 
148  ROS_DEBUG_NAMED(LOGNAME, "Trying to allocate kinematics solver for group '%s'", jmg->getName().c_str());
149 
150  std::map<std::string, std::vector<std::string>>::const_iterator it =
152  if (it == possible_kinematics_solvers_.end())
153  {
154  ROS_DEBUG_NAMED(LOGNAME, "No kinematics solver available for this group");
155  return result;
156  }
157 
158  const std::string& base = links.front()->getParentJointModel()->getParentLinkModel() ?
159  links.front()->getParentJointModel()->getParentLinkModel()->getName() :
160  jmg->getParentModel().getModelFrame();
161 
162  // just to be sure, do not call the same pluginlib instance allocation function in parallel
163  boost::mutex::scoped_lock slock(lock_);
164  for (std::size_t i = 0; !result && i < it->second.size(); ++i)
165  {
166  try
167  {
168  result = kinematics_loader_->createUniqueInstance(it->second[i]);
169  if (result)
170  {
171  // choose the tip of the IK solver
172  const std::vector<std::string> tips = chooseTipFrames(jmg);
173 
174  // choose search resolution
175  double search_res = search_res_.find(jmg->getName())->second[i]; // we know this exists, by construction
176 
177  if (!result->initialize(jmg->getParentModel(), jmg->getName(),
178  (base.empty() || base[0] != '/') ? base : base.substr(1), tips, search_res) &&
179  // on failure: fallback to old method (TODO: remove in future)
180  !result->initialize(robot_description_, jmg->getName(),
181  (base.empty() || base[0] != '/') ? base : base.substr(1), tips, search_res))
182  {
183  ROS_ERROR_NAMED(LOGNAME, "Kinematics solver of type '%s' could not be initialized for group '%s'",
184  it->second[i].c_str(), jmg->getName().c_str());
185  result.reset();
186  continue;
187  }
188 
189  result->setDefaultTimeout(jmg->getDefaultIKTimeout());
191  "Successfully allocated and initialized a kinematics solver of type '%s' with search "
192  "resolution %lf for group '%s' at address %p",
193  it->second[i].c_str(), search_res, jmg->getName().c_str(), result.get());
194  break;
195  }
196  }
198  {
199  ROS_ERROR_NAMED(LOGNAME, "The kinematics plugin (%s) failed to load. Error: %s", it->first.c_str(), e.what());
200  }
201  }
202 
203  if (!result)
204  {
205  ROS_DEBUG_NAMED(LOGNAME, "No usable kinematics solver was found for this group.\n"
206  "Did you load kinematics.yaml into your node's namespace?");
207  }
208  return result;
209  }
210 
211  // cache solver between two consecutive calls
212  // first call in RobotModelLoader::loadKinematicsSolvers() is just to check suitability for jmg
213  // second call in JointModelGroup::setSolverAllocators() is to actually retrieve the instance for use
214  kinematics::KinematicsBasePtr allocKinematicsSolverWithCache(const moveit::core::JointModelGroup* jmg)
215  {
216  boost::mutex::scoped_lock slock(cache_lock_);
217  kinematics::KinematicsBasePtr& cached = instances_[jmg];
218  if (cached.unique())
219  return std::move(cached); // pass on unique instance
220 
221  // create a new instance and store in instances_
223  return cached;
224  }
225 
226  void status() const
227  {
228  for (std::map<std::string, std::vector<std::string>>::const_iterator it = possible_kinematics_solvers_.begin();
229  it != possible_kinematics_solvers_.end(); ++it)
230  for (std::size_t i = 0; i < it->second.size(); ++i)
231  ROS_INFO_NAMED(LOGNAME, "Solver for group '%s': '%s' (search resolution = %lf)", it->first.c_str(),
232  it->second[i].c_str(), search_res_.at(it->first)[i]);
233  }
234 
235 private:
236  std::string robot_description_;
237  std::map<std::string, std::vector<std::string>> possible_kinematics_solvers_;
238  std::map<std::string, std::vector<double>> search_res_;
239  std::map<std::string, std::vector<std::string>> iksolver_to_tip_links_; // a map between each ik solver and a vector
240  // of custom-specified tip link(s)
241  std::shared_ptr<pluginlib::ClassLoader<kinematics::KinematicsBase>> kinematics_loader_;
242  std::map<const moveit::core::JointModelGroup*, kinematics::KinematicsBasePtr> instances_;
243  boost::mutex lock_;
244  boost::mutex cache_lock_;
245 };
246 
248 {
249  if (loader_)
250  loader_->status();
251  else
252  ROS_INFO_NAMED(LOGNAME, "Loader function was never required");
253 }
254 
256 {
258  moveit::tools::Profiler::ScopedBlock prof_block("KinematicsPluginLoader::getLoaderFunction");
259 
260  if (loader_)
261  return [&loader = *loader_](const moveit::core::JointModelGroup* jmg) {
262  return loader.allocKinematicsSolverWithCache(jmg);
263  };
264 
266  robot_description_ = rml.getRobotDescription();
267  return getLoaderFunction(rml.getSRDF());
268 }
269 
271 {
273  moveit::tools::Profiler::ScopedBlock prof_block("KinematicsPluginLoader::getLoaderFunction(SRDF)");
274 
275  if (!loader_)
276  {
277  ROS_DEBUG_NAMED(LOGNAME, "Configuring kinematics solvers");
278  groups_.clear();
279 
280  std::map<std::string, std::vector<std::string>> possible_kinematics_solvers;
281  std::map<std::string, std::vector<double>> search_res;
282  std::map<std::string, std::vector<std::string>> iksolver_to_tip_links;
283 
284  if (srdf_model)
285  {
286  const std::vector<srdf::Model::Group>& known_groups = srdf_model->getGroups();
287  if (default_search_resolution_ <= std::numeric_limits<double>::epsilon())
289 
290  if (default_solver_plugin_.empty())
291  {
292  ROS_DEBUG_NAMED(LOGNAME, "Loading settings for kinematics solvers from the ROS param server ...");
293 
294  // read data using ROS params
295  ros::NodeHandle nh("~");
296 
297  // read the list of plugin names for possible kinematics solvers
298  for (const srdf::Model::Group& known_group : known_groups)
299  {
300  std::string base_param_name = known_group.name_;
301  ROS_DEBUG_NAMED("kinematics_plugin_loader", "Looking for param %s ",
302  (base_param_name + "/kinematics_solver").c_str());
303  std::string ksolver_param_name;
304  bool found = nh.searchParam(base_param_name + "/kinematics_solver", ksolver_param_name);
305  if (!found || !nh.hasParam(ksolver_param_name))
306  {
307  base_param_name = robot_description_ + "_kinematics/" + known_group.name_;
308  ROS_DEBUG_NAMED(LOGNAME, "Looking for param %s ", (base_param_name + "/kinematics_solver").c_str());
309  found = nh.searchParam(base_param_name + "/kinematics_solver", ksolver_param_name);
310  }
311  if (found)
312  {
313  ROS_DEBUG_NAMED(LOGNAME, "Found param %s", ksolver_param_name.c_str());
314  std::string ksolver;
315  if (nh.getParam(ksolver_param_name, ksolver))
316  {
317  std::stringstream ss(ksolver);
318  bool first = true;
319  while (ss.good() && !ss.eof())
320  {
321  if (first)
322  {
323  first = false;
324  groups_.push_back(known_group.name_);
325  }
326  std::string solver;
327  ss >> solver >> std::ws;
328  possible_kinematics_solvers[known_group.name_].push_back(solver);
329  ROS_DEBUG_NAMED(LOGNAME, "Using kinematics solver '%s' for group '%s'.", solver.c_str(),
330  known_group.name_.c_str());
331  }
332  }
333  }
334 
335  std::string ksolver_timeout_param_name;
336  if (nh.searchParam(base_param_name + "/kinematics_solver_timeout", ksolver_timeout_param_name))
337  {
338  double ksolver_timeout;
339  if (nh.getParam(ksolver_timeout_param_name, ksolver_timeout))
340  ik_timeout_[known_group.name_] = ksolver_timeout;
341  else
342  { // just in case this is an int
343  int ksolver_timeout_i;
344  if (nh.getParam(ksolver_timeout_param_name, ksolver_timeout_i))
345  ik_timeout_[known_group.name_] = ksolver_timeout_i;
346  }
347  }
348 
349  // TODO: Remove in future release (deprecated in PR #1288, Jan-2019, Melodic)
350  std::string ksolver_attempts_param_name;
351  if (nh.searchParam(base_param_name + "/kinematics_solver_attempts", ksolver_attempts_param_name) &&
352  nh.hasParam(ksolver_attempts_param_name))
353  {
355  "Kinematics solver doesn't support #attempts anymore, but only a timeout.\n"
356  "Please remove the parameter '%s' from your configuration.",
357  ksolver_attempts_param_name.c_str());
358  }
359 
360  std::string ksolver_res_param_name;
361  if (nh.searchParam(base_param_name + "/kinematics_solver_search_resolution", ksolver_res_param_name))
362  {
363  std::string ksolver_res;
364  if (nh.getParam(ksolver_res_param_name, ksolver_res))
365  {
366  std::stringstream ss(ksolver_res);
367  while (ss.good() && !ss.eof())
368  {
369  double res;
370  ss >> res >> std::ws;
371  search_res[known_group.name_].push_back(res);
372  }
373  }
374  else
375  { // handle the case this param is just one value and parsed as a double
376  double res;
377  if (nh.getParam(ksolver_res_param_name, res))
378  search_res[known_group.name_].push_back(res);
379  else
380  {
381  int res_i;
382  if (nh.getParam(ksolver_res_param_name, res_i))
383  search_res[known_group.name_].push_back(res_i);
384  }
385  }
386  }
387 
388  // Allow a kinematic solver's tip link to be specified on the rosparam server
389  // Depreciated in favor of array version now
390  std::string ksolver_ik_link_param_name;
391  if (nh.searchParam(base_param_name + "/kinematics_solver_ik_link", ksolver_ik_link_param_name))
392  {
393  std::string ksolver_ik_link;
394  if (nh.getParam(ksolver_ik_link_param_name, ksolver_ik_link)) // has a custom rosparam-based tip link
395  {
396  ROS_WARN_STREAM_NAMED(LOGNAME, "Using kinematics_solver_ik_link rosparam is "
397  "deprecated in favor of kinematics_solver_ik_links "
398  "rosparam array.");
399  iksolver_to_tip_links[known_group.name_].push_back(ksolver_ik_link);
400  }
401  }
402 
403  // Allow a kinematic solver's tip links to be specified on the rosparam server as an array
404  std::string ksolver_ik_links_param_name;
405  if (nh.searchParam(base_param_name + "/kinematics_solver_ik_links", ksolver_ik_links_param_name))
406  {
407  XmlRpc::XmlRpcValue ksolver_ik_links;
408  if (nh.getParam(ksolver_ik_links_param_name, ksolver_ik_links)) // has custom rosparam-based tip link(s)
409  {
410  if (ksolver_ik_links.getType() != XmlRpc::XmlRpcValue::TypeArray)
411  {
412  ROS_WARN_STREAM_NAMED(LOGNAME, "rosparam '" << ksolver_ik_links_param_name
413  << "' should be an XmlRpc "
414  "value type 'Array'");
415  }
416  else
417  {
418  for (int32_t j = 0; j < ksolver_ik_links.size(); ++j) // NOLINT(modernize-loop-convert)
419  {
420  ROS_ASSERT(ksolver_ik_links[j].getType() == XmlRpc::XmlRpcValue::TypeString);
421  ROS_DEBUG_STREAM_NAMED(LOGNAME, "found tip " << static_cast<std::string>(ksolver_ik_links[j])
422  << " for group " << known_group.name_);
423  iksolver_to_tip_links[known_group.name_].push_back(static_cast<std::string>(ksolver_ik_links[j]));
424  }
425  }
426  }
427  }
428 
429  // make sure there is a default resolution at least specified for every solver (in case it was not specified
430  // on the param server)
431  while (search_res[known_group.name_].size() < possible_kinematics_solvers[known_group.name_].size())
432  search_res[known_group.name_].push_back(default_search_resolution_);
433  }
434  }
435  else
436  {
437  ROS_DEBUG_NAMED(LOGNAME, "Using specified default settings for kinematics solvers ...");
438  for (const srdf::Model::Group& known_group : known_groups)
439  {
440  possible_kinematics_solvers[known_group.name_].resize(1, default_solver_plugin_);
441  search_res[known_group.name_].resize(1, default_search_resolution_);
442  ik_timeout_[known_group.name_] = default_solver_timeout_;
443  groups_.push_back(known_group.name_);
444  }
445  }
446  }
447 
448  loader_ = std::make_shared<KinematicsLoaderImpl>(robot_description_, possible_kinematics_solvers, search_res,
449  iksolver_to_tip_links);
450  }
451 
452  return [&loader = *loader_](const moveit::core::JointModelGroup* jmg) {
453  return loader.allocKinematicsSolverWithCache(jmg);
454  };
455 }
456 } // namespace kinematics_plugin_loader
XmlRpc::XmlRpcValue::size
int size() const
moveit::core::RobotModel::getModelFrame
const std::string & getModelFrame() const
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::iksolver_to_tip_links_
std::map< std::string, std::vector< std::string > > iksolver_to_tip_links_
Definition: kinematics_plugin_loader.cpp:271
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::allocKinematicsSolverWithCache
kinematics::KinematicsBasePtr allocKinematicsSolverWithCache(const moveit::core::JointModelGroup *jmg)
Definition: kinematics_plugin_loader.cpp:246
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::search_res_
std::map< std::string, std::vector< double > > search_res_
Definition: kinematics_plugin_loader.cpp:270
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::lock_
boost::mutex lock_
Definition: kinematics_plugin_loader.cpp:275
kinematics::KinematicsBase::DEFAULT_SEARCH_DISCRETIZATION
static const MOVEIT_KINEMATICS_BASE_EXPORT double DEFAULT_SEARCH_DISCRETIZATION
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
kinematics_plugin_loader::KinematicsPluginLoader::default_solver_plugin_
std::string default_solver_plugin_
Definition: kinematics_plugin_loader.h:145
cached
AABB< S > cached
kinematics_plugin_loader::KinematicsPluginLoader::ik_timeout_
std::map< std::string, double > ik_timeout_
Definition: kinematics_plugin_loader.h:142
srdf::ModelSharedPtr
std::shared_ptr< Model > ModelSharedPtr
moveit::core::JointModelGroup::getParentModel
const RobotModel & getParentModel() const
ROS_WARN_ONCE_NAMED
#define ROS_WARN_ONCE_NAMED(name,...)
moveit::tools::Profiler::ScopedStart
kinematics_plugin_loader::KinematicsPluginLoader::default_solver_timeout_
double default_solver_timeout_
Definition: kinematics_plugin_loader.h:146
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::KinematicsLoaderImpl
KinematicsLoaderImpl(const std::string &robot_description, const std::map< std::string, std::vector< std::string >> &possible_kinematics_solvers, const std::map< std::string, std::vector< double >> &search_res, const std::map< std::string, std::vector< std::string >> &iksolver_to_tip_links)
Pimpl Implementation of KinematicsLoader.
Definition: kinematics_plugin_loader.cpp:94
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::possible_kinematics_solvers_
std::map< std::string, std::vector< std::string > > possible_kinematics_solvers_
Definition: kinematics_plugin_loader.cpp:269
kinematics_plugin_loader
Definition: kinematics_plugin_loader.h:44
kinematics_plugin_loader::KinematicsPluginLoader::robot_description_
std::string robot_description_
Definition: kinematics_plugin_loader.h:135
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::robot_description_
std::string robot_description_
Definition: kinematics_plugin_loader.cpp:268
moveit::core::JointModelGroup::getLinkModels
const std::vector< const LinkModel * > & getLinkModels() const
kinematics_plugin_loader::KinematicsPluginLoader::getLoaderFunction
moveit::core::SolverAllocatorFn getLoaderFunction()
Get a function pointer that allocates and initializes a kinematics solver. If not previously called,...
Definition: kinematics_plugin_loader.cpp:287
kinematics_plugin_loader::KinematicsPluginLoader::groups_
std::vector< std::string > groups_
Definition: kinematics_plugin_loader.h:141
pluginlib::PluginlibException
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::allocKinematicsSolver
kinematics::KinematicsBasePtr allocKinematicsSolver(const moveit::core::JointModelGroup *jmg)
Definition: kinematics_plugin_loader.cpp:159
moveit::core::JointModelGroup::getName
const std::string & getName() const
kinematics_plugin_loader::KinematicsPluginLoader::default_search_resolution_
double default_search_resolution_
Definition: kinematics_plugin_loader.h:136
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::chooseTipFrames
std::vector< std::string > chooseTipFrames(const moveit::core::JointModelGroup *jmg)
Helper function to decide which, and how many, tip frames a planning group has.
Definition: kinematics_plugin_loader.cpp:120
moveit::core::SolverAllocatorFn
boost::function< kinematics::KinematicsBasePtr(const JointModelGroup *)> SolverAllocatorFn
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
kinematics_plugin_loader::KinematicsPluginLoader::loader_
KinematicsLoaderImplPtr loader_
Definition: kinematics_plugin_loader.h:139
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
XmlRpc::XmlRpcValue::TypeString
TypeString
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::instances_
std::map< const moveit::core::JointModelGroup *, kinematics::KinematicsBasePtr > instances_
Definition: kinematics_plugin_loader.cpp:274
rdf_loader::RDFLoader
Definition: rdf_loader.h:80
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
class_loader.hpp
XmlRpc::XmlRpcValue::getType
const Type & getType() const
ROS_WARN_STREAM_NAMED
#define ROS_WARN_STREAM_NAMED(name, args)
XmlRpc::XmlRpcValue::TypeArray
TypeArray
kinematics_plugin_loader::LOGNAME
static const std::string LOGNAME
Definition: kinematics_plugin_loader.cpp:82
moveit::core::JointModelGroup::getDefaultIKTimeout
double getDefaultIKTimeout() const
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::kinematics_loader_
std::shared_ptr< pluginlib::ClassLoader< kinematics::KinematicsBase > > kinematics_loader_
Definition: kinematics_plugin_loader.cpp:273
kinematics_plugin_loader::KinematicsPluginLoader::status
void status() const
Definition: kinematics_plugin_loader.cpp:279
kinematics_plugin_loader.h
moveit::tools::Profiler::ScopedBlock
moveit::core::JointModelGroup
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::cache_lock_
boost::mutex cache_lock_
Definition: kinematics_plugin_loader.cpp:276
srdf::Model::Group
profiler.h
ROS_ASSERT
#define ROS_ASSERT(cond)
rdf_loader.h
XmlRpc::XmlRpcValue
ros::NodeHandle
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl::status
void status() const
Definition: kinematics_plugin_loader.cpp:258


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Jun 27 2024 02:26:29