robot_model_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 */
36 
37 #ifndef MOVEIT_PLANNING_MODELS_LOADER_ROBOT_MODEL_LOADER_
38 #define MOVEIT_PLANNING_MODELS_LOADER_ROBOT_MODEL_LOADER_
39 
44 
46 {
48 
51 {
52 public:
54  struct Options
55  {
56  Options(const std::string& robot_description = "robot_description")
57  : robot_description_(robot_description), urdf_doc_(NULL), srdf_doc_(NULL), load_kinematics_solvers_(true)
58  {
59  }
60 
61  Options(const std::string& urdf_string, const std::string& srdf_string)
62  : urdf_string_(urdf_string)
63  , srdf_string_(srdf_string)
64  , urdf_doc_(NULL)
65  , srdf_doc_(NULL)
67  {
68  }
69 
70  Options(TiXmlDocument* urdf_doc, TiXmlDocument* srdf_doc)
71  : urdf_doc_(urdf_doc), srdf_doc_(srdf_doc), load_kinematics_solvers_(true)
72  {
73  }
74 
78  std::string robot_description_;
79 
82  std::string urdf_string_, srdf_string_;
83 
85  TiXmlDocument *urdf_doc_, *srdf_doc_;
86 
90  };
91 
93  RobotModelLoader(const Options& opt = Options());
94 
95  RobotModelLoader(const std::string& robot_description, bool load_kinematics_solvers = true);
96 
98 
100  const robot_model::RobotModelPtr& getModel() const
101  {
102  return model_;
103  }
104 
106  const std::string& getRobotDescription() const
107  {
108  return rdf_loader_->getRobotDescription();
109  }
110 
112  const urdf::ModelInterfaceSharedPtr& getURDF() const
113  {
114  return rdf_loader_->getURDF();
115  }
116 
119  {
120  return rdf_loader_->getSRDF();
121  }
122 
124  const rdf_loader::RDFLoaderPtr& getRDFLoader() const
125  {
126  return rdf_loader_;
127  }
128 
131  const kinematics_plugin_loader::KinematicsPluginLoaderPtr& getKinematicsPluginLoader() const
132  {
133  return kinematics_loader_;
134  }
135 
138  void loadKinematicsSolvers(const kinematics_plugin_loader::KinematicsPluginLoaderPtr& kloader =
139  kinematics_plugin_loader::KinematicsPluginLoaderPtr());
140 
141 private:
142  void configure(const Options& opt);
143 
144  robot_model::RobotModelPtr model_;
145  rdf_loader::RDFLoaderPtr rdf_loader_;
146  kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_;
147 };
148 }
149 #endif
const srdf::ModelSharedPtr & getSRDF() const
Get the parsed SRDF model.
void loadKinematicsSolvers(const kinematics_plugin_loader::KinematicsPluginLoaderPtr &kloader=kinematics_plugin_loader::KinematicsPluginLoaderPtr())
Load the kinematics solvers into the kinematic model. This is done by default, unless disabled explic...
TiXmlDocument * urdf_doc_
The parsed XML content of the URDF and SRDF documents.
const rdf_loader::RDFLoaderPtr & getRDFLoader() const
Get the instance of rdf_loader::RDFLoader that was used to load the robot description.
Options(const std::string &robot_description="robot_description")
Options(TiXmlDocument *urdf_doc, TiXmlDocument *srdf_doc)
kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_
std::string robot_description_
The string name corresponding to the ROS param where the URDF is loaded; Using the same parameter nam...
bool load_kinematics_solvers_
Flag indicating whether the kinematics solvers should be loaded as well, using specified ROS paramete...
Structure that encodes the options to be passed to the RobotModelLoader constructor.
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
RobotModelLoader(const Options &opt=Options())
Default constructor.
Options(const std::string &urdf_string, const std::string &srdf_string)
const std::string & getRobotDescription() const
Get the resolved parameter name for the robot description.
const robot_model::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
std::string urdf_string_
The string content of the URDF and SRDF documents. Loading from string is attempted only if loading f...
MOVEIT_CLASS_FORWARD(RobotModelLoader)
const kinematics_plugin_loader::KinematicsPluginLoaderPtr & getKinematicsPluginLoader() const
Get the kinematics solvers plugin loader.


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sun Oct 18 2020 13:17:33