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 #pragma once
38 
43 
45 {
46 MOVEIT_CLASS_FORWARD(RobotModelLoader); // Defines RobotModelLoaderPtr, ConstPtr, WeakPtr... etc
47 
48 class RobotModelLoader
49 {
50 public:
52  struct Options
53  {
54  Options(const std::string& robot_description = "robot_description")
55  : robot_description_(robot_description), load_kinematics_solvers_(true)
56  {
57  }
58 
59  Options(const std::string& urdf_string, const std::string& srdf_string)
60  : urdf_string_(urdf_string), srdf_string_(srdf_string), load_kinematics_solvers_(true)
61  {
62  }
63 
67  std::string robot_description_;
68 
71  std::string urdf_string_, srdf_string_;
72 
76  };
77 
79  RobotModelLoader(const Options& opt = Options());
80 
81  RobotModelLoader(const std::string& robot_description, bool load_kinematics_solvers = true);
82 
84 
86  const moveit::core::RobotModelPtr& getModel() const
87  {
88  return model_;
89  }
90 
92  const std::string& getRobotDescription() const
93  {
94  return rdf_loader_->getRobotDescription();
95  }
96 
98  const urdf::ModelInterfaceSharedPtr& getURDF() const
99  {
100  return rdf_loader_->getURDF();
101  }
102 
104  const srdf::ModelSharedPtr& getSRDF() const
105  {
106  return rdf_loader_->getSRDF();
107  }
108 
110  const rdf_loader::RDFLoaderPtr& getRDFLoader() const
111  {
112  return rdf_loader_;
113  }
114 
117  const kinematics_plugin_loader::KinematicsPluginLoaderPtr& getKinematicsPluginLoader() const
118  {
119  return kinematics_loader_;
120  }
121 
124  void loadKinematicsSolvers(const kinematics_plugin_loader::KinematicsPluginLoaderPtr& kloader =
125  kinematics_plugin_loader::KinematicsPluginLoaderPtr());
126 
127 private:
128  void configure(const Options& opt);
129 
130  moveit::core::RobotModelPtr model_;
131  rdf_loader::RDFLoaderPtr rdf_loader_;
132  kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_;
133 };
134 } // namespace robot_model_loader
robot_model.h
robot_model_loader::RobotModelLoader::model_
moveit::core::RobotModelPtr model_
Definition: robot_model_loader.h:162
robot_model_loader::RobotModelLoader::getRobotDescription
const std::string & getRobotDescription() const
Get the resolved parameter name for the robot description.
Definition: robot_model_loader.h:124
robot_model_loader::RobotModelLoader::getSRDF
const srdf::ModelSharedPtr & getSRDF() const
Get the parsed SRDF model.
Definition: robot_model_loader.h:136
robot_model_loader
Definition: robot_model_loader.h:44
robot_model_loader::RobotModelLoader::rdf_loader_
rdf_loader::RDFLoaderPtr rdf_loader_
Definition: robot_model_loader.h:163
robot_model_loader::RobotModelLoader::getKinematicsPluginLoader
const kinematics_plugin_loader::KinematicsPluginLoaderPtr & getKinematicsPluginLoader() const
Get the kinematics solvers plugin loader.
Definition: robot_model_loader.h:149
srdf::ModelSharedPtr
std::shared_ptr< Model > ModelSharedPtr
robot_model_loader::RobotModelLoader
Definition: robot_model_loader.h:80
robot_model_loader::RobotModelLoader::Options::urdf_string_
std::string urdf_string_
The string content of the URDF and SRDF documents. Loading from string is attempted only if loading f...
Definition: robot_model_loader.h:103
robot_model_loader::RobotModelLoader::Options::load_kinematics_solvers_
bool load_kinematics_solvers_
Flag indicating whether the kinematics solvers should be loaded as well, using specified ROS paramete...
Definition: robot_model_loader.h:107
robot_model_loader::RobotModelLoader::configure
void configure(const Options &opt)
Definition: robot_model_loader.cpp:120
robot_model_loader::RobotModelLoader::Options
Structure that encodes the options to be passed to the RobotModelLoader constructor.
Definition: robot_model_loader.h:84
robot_model_loader::RobotModelLoader::RobotModelLoader
RobotModelLoader(const Options &opt=Options())
Default constructor.
Definition: robot_model_loader.cpp:85
robot_model_loader::RobotModelLoader::getRDFLoader
const rdf_loader::RDFLoaderPtr & getRDFLoader() const
Get the instance of rdf_loader::RDFLoader that was used to load the robot description.
Definition: robot_model_loader.h:142
robot_model_loader::RobotModelLoader::~RobotModelLoader
~RobotModelLoader()
Definition: robot_model_loader.cpp:90
class_forward.h
robot_model_loader::RobotModelLoader::Options::robot_description_
std::string robot_description_
The string name corresponding to the ROS param where the URDF is loaded; Using the same parameter nam...
Definition: robot_model_loader.h:99
kinematics_plugin_loader.h
robot_model_loader::RobotModelLoader::Options::srdf_string_
std::string srdf_string_
Definition: robot_model_loader.h:103
robot_model_loader::RobotModelLoader::loadKinematicsSolvers
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...
Definition: robot_model_loader.cpp:201
robot_model_loader::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(RobotModelLoader)
robot_model_loader::RobotModelLoader::kinematics_loader_
kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_
Definition: robot_model_loader.h:164
robot_model_loader::RobotModelLoader::Options::Options
Options(const std::string &robot_description="robot_description")
Definition: robot_model_loader.h:86
rdf_loader.h
robot_model_loader::RobotModelLoader::getURDF
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
Definition: robot_model_loader.h:130
robot_model_loader::RobotModelLoader::getModel
const moveit::core::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
Definition: robot_model_loader.h:118


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Apr 18 2024 02:24:19