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 #pragma once
38 
39 #include <boost/function.hpp>
43 
45 {
46 MOVEIT_CLASS_FORWARD(KinematicsPluginLoader); // Defines KinematicsPluginLoaderPtr, ConstPtr, WeakPtr... etc
47 
50 {
51 public:
57  KinematicsPluginLoader(const std::string& robot_description = "robot_description",
58  double default_search_resolution = 0.0)
59  : robot_description_(robot_description), default_search_resolution_(default_search_resolution)
60  {
61  }
62 
70  KinematicsPluginLoader(const std::string& solver_plugin, double solve_timeout, unsigned int /*ik_attempts*/,
71  const std::string& robot_description = "robot_description",
72  double default_search_resolution = 0.0)
73  : robot_description_(robot_description)
74  , default_search_resolution_(default_search_resolution)
75  , default_solver_plugin_(solver_plugin)
76  , default_solver_timeout_(solve_timeout)
77  {
78  }
79 
83 
87 
89  const std::vector<std::string>& getKnownGroups() const
90  {
91  return groups_;
92  }
93 
95  const std::map<std::string, double>& getIKTimeout() const
96  {
97  return ik_timeout_;
98  }
99 
100  void status() const;
101 
102 private:
103  std::string robot_description_;
105 
106  MOVEIT_CLASS_FORWARD(KinematicsLoaderImpl); // Defines KinematicsLoaderImplPtr, ConstPtr, WeakPtr... etc
107  KinematicsLoaderImplPtr loader_;
108 
109  std::vector<std::string> groups_;
110  std::map<std::string, double> ik_timeout_;
111 
112  // default configuration
113  std::string default_solver_plugin_;
115 };
116 } // namespace kinematics_plugin_loader
robot_model.h
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsLoaderImpl
Definition: kinematics_plugin_loader.cpp:84
kinematics_plugin_loader::KinematicsPluginLoader::default_solver_plugin_
std::string default_solver_plugin_
Definition: kinematics_plugin_loader.h:145
kinematics_plugin_loader::KinematicsPluginLoader::getIKTimeout
const std::map< std::string, double > & getIKTimeout() const
Get a map from group name to default IK timeout.
Definition: kinematics_plugin_loader.h:127
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
kinematics_plugin_loader::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(KinematicsPluginLoader)
kinematics_plugin_loader::KinematicsPluginLoader
Helper class for loading kinematics solvers.
Definition: kinematics_plugin_loader.h:81
kinematics_plugin_loader::KinematicsPluginLoader::default_solver_timeout_
double default_solver_timeout_
Definition: kinematics_plugin_loader.h:146
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::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
kinematics_plugin_loader::KinematicsPluginLoader::getKnownGroups
const std::vector< std::string > & getKnownGroups() const
Get the groups for which the function pointer returned by getLoaderFunction() can allocate a solver.
Definition: kinematics_plugin_loader.h:121
kinematics_plugin_loader::KinematicsPluginLoader::default_search_resolution_
double default_search_resolution_
Definition: kinematics_plugin_loader.h:136
kinematics_plugin_loader::KinematicsPluginLoader::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(KinematicsLoaderImpl)
moveit::core::SolverAllocatorFn
boost::function< kinematics::KinematicsBasePtr(const JointModelGroup *)> SolverAllocatorFn
kinematics_plugin_loader::KinematicsPluginLoader::loader_
KinematicsLoaderImplPtr loader_
Definition: kinematics_plugin_loader.h:139
kinematics_plugin_loader::KinematicsPluginLoader::status
void status() const
Definition: kinematics_plugin_loader.cpp:279
class_forward.h
kinematics_base.h
kinematics_plugin_loader::KinematicsPluginLoader::KinematicsPluginLoader
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...
Definition: kinematics_plugin_loader.h:89


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:03