kinematics_plugin_loader.h
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 
37 #ifndef MOVEIT_KINEMATICS_PLUGIN_LOADER_
38 #define MOVEIT_KINEMATICS_PLUGIN_LOADER_
39 
40 #include <boost/function.hpp>
44 
46 {
48 
51 {
52 public:
58  KinematicsPluginLoader(const std::string& robot_description = "robot_description",
59  double default_search_resolution = 0.0)
60  : robot_description_(robot_description), default_search_resolution_(default_search_resolution)
61  {
62  }
63 
71  KinematicsPluginLoader(const std::string& solver_plugin, double solve_timeout, unsigned int ik_attempts,
72  const std::string& robot_description = "robot_description",
73  double default_search_resolution = 0.0)
74  : robot_description_(robot_description)
75  , default_search_resolution_(default_search_resolution)
76  , default_solver_plugin_(solver_plugin)
77  , default_solver_timeout_(solve_timeout)
78  , default_ik_attempts_(ik_attempts)
79  {
80  }
81 
84  robot_model::SolverAllocatorFn getLoaderFunction();
85 
88  robot_model::SolverAllocatorFn getLoaderFunction(const srdf::ModelSharedPtr& srdf_model);
89 
91  const std::vector<std::string>& getKnownGroups() const
92  {
93  return groups_;
94  }
95 
97  const std::map<std::string, double>& getIKTimeout() const
98  {
99  return ik_timeout_;
100  }
101 
103  const std::map<std::string, unsigned int>& getIKAttempts() const
104  {
105  return ik_attempts_;
106  }
107 
108  void status() const;
109 
110 private:
111  std::string robot_description_;
113 
115  KinematicsLoaderImplPtr loader_;
116 
117  std::vector<std::string> groups_;
118  std::map<std::string, double> ik_timeout_;
119  std::map<std::string, unsigned int> ik_attempts_;
120 
121  // default configuration
124  unsigned int default_ik_attempts_;
125 };
126 }
127 
128 #endif
KinematicsPluginLoader(const std::string &robot_description="robot_description", double default_search_resolution=0.0)
Load the kinematics solvers based on information on the ROS parameter server. Take as optional argume...
const std::vector< std::string > & getKnownGroups() const
Get the groups for which the function pointer returned by getLoaderFunction() can allocate a solver...
std::map< std::string, unsigned int > ik_attempts_
const std::map< std::string, double > & getIKTimeout() const
Get a map from group name to default IK timeout.
const std::map< std::string, unsigned int > & getIKAttempts() const
Get a map from group name to default IK attempts.
MOVEIT_CLASS_FORWARD(KinematicsPluginLoader)
KinematicsPluginLoader(const std::string &solver_plugin, double solve_timeout, unsigned int ik_attempts, const std::string &robot_description="robot_description", double default_search_resolution=0.0)
Use a default kinematics solver (solver_plugin) for all the groups in the robot model. The default timeout for the solver is solve_timeout and the default number of IK attempts is ik_attempts. Take as optional argument the name of the ROS parameter under which the robot description can be found. This is passed to the kinematics solver initialization as well as used to read the SRDF document when needed.
robot_model::SolverAllocatorFn getLoaderFunction()
Get a function pointer that allocates and initializes a kinematics solver. If not previously called...
Helper class for loading kinematics solvers.


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Wed Jul 10 2019 04:03:32