moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
50 {
51 public:
53  struct Options
54  {
55  Options(const std::string& robot_description = "robot_description")
56  : robot_description_(robot_description), load_kinematics_solvers_(true)
57  {
58  }
59 
60  Options(const std::string& urdf_string, const std::string& srdf_string)
61  : urdf_string_(urdf_string), srdf_string_(srdf_string), load_kinematics_solvers_(true)
62  {
63  }
64 
68  std::string robot_description_;
69 
72  std::string urdf_string_, srdf_string_;
73 
77  };
78 
80  RobotModelLoader(const rclcpp::Node::SharedPtr& node, const Options& opt = Options());
81 
82  RobotModelLoader(const rclcpp::Node::SharedPtr& node, const std::string& robot_description,
83  bool load_kinematics_solvers = true);
84 
86 
88  const moveit::core::RobotModelPtr& getModel() const
89  {
90  return model_;
91  }
92 
94  const std::string& getRobotDescription() const
95  {
96  return rdf_loader_->getRobotDescription();
97  }
98 
100  const urdf::ModelInterfaceSharedPtr& getURDF() const
101  {
102  return rdf_loader_->getURDF();
103  }
104 
106  const srdf::ModelSharedPtr& getSRDF() const
107  {
108  return rdf_loader_->getSRDF();
109  }
110 
112  const rdf_loader::RDFLoaderPtr& getRDFLoader() const
113  {
114  return rdf_loader_;
115  }
116 
119  const kinematics_plugin_loader::KinematicsPluginLoaderPtr& getKinematicsPluginLoader() const
120  {
121  return kinematics_loader_;
122  }
123 
126  void loadKinematicsSolvers(const kinematics_plugin_loader::KinematicsPluginLoaderPtr& kloader =
127  kinematics_plugin_loader::KinematicsPluginLoaderPtr());
128 
129 private:
130  void configure(const Options& opt);
131 
132  moveit::core::RobotModelPtr model_;
133  rdf_loader::RDFLoaderPtr rdf_loader_;
134  kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_;
135  const rclcpp::Node::SharedPtr node_;
136 };
137 } // namespace robot_model_loader
const rdf_loader::RDFLoaderPtr & getRDFLoader() const
Get the instance of rdf_loader::RDFLoader that was used to load the robot description.
const moveit::core::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
const kinematics_plugin_loader::KinematicsPluginLoaderPtr & getKinematicsPluginLoader() const
Get the kinematics solvers plugin loader.
const srdf::ModelSharedPtr & getSRDF() const
Get the parsed SRDF model.
RobotModelLoader(const rclcpp::Node::SharedPtr &node, const Options &opt=Options())
Default constructor.
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF 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...
const std::string & getRobotDescription() const
Get the resolved parameter name for the robot description.
MOVEIT_CLASS_FORWARD(RobotModelLoader)
Structure that encodes the options to be passed to the RobotModelLoader constructor.
Options(const std::string &robot_description="robot_description")
Options(const std::string &urdf_string, const std::string &srdf_string)
std::string robot_description_
The string name corresponding to the ROS param where the URDF is loaded; Using the same parameter nam...
std::string urdf_string_
The string content of the URDF and SRDF documents. Loading from string is attempted only if loading f...
bool load_kinematics_solvers_
Flag indicating whether the kinematics solvers should be loaded as well, using specified ROS paramete...