Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
robot_model_loader::RobotModelLoader Class Reference

#include <robot_model_loader.h>

Classes

struct  Options
 Structure that encodes the options to be passed to the RobotModelLoader constructor. More...
 

Public Member Functions

const kinematics_plugin_loader::KinematicsPluginLoaderPtr & getKinematicsPluginLoader () const
 Get the kinematics solvers plugin loader. More...
 
const moveit::core::RobotModelPtr & getModel () const
 Get the constructed planning_models::RobotModel. More...
 
const rdf_loader::RDFLoaderPtr & getRDFLoader () const
 Get the instance of rdf_loader::RDFLoader that was used to load the robot description. More...
 
const std::string & getRobotDescription () const
 Get the resolved parameter name for the robot description. More...
 
const srdf::ModelSharedPtrgetSRDF () const
 Get the parsed SRDF model. More...
 
const urdf::ModelInterfaceSharedPtr & getURDF () const
 Get the parsed URDF model. More...
 
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 explicitly by the options passed to the constructor. More...
 
 RobotModelLoader (const Options &opt=Options())
 Default constructor. More...
 
 RobotModelLoader (const std::string &robot_description, bool load_kinematics_solvers=true)
 
 ~RobotModelLoader ()
 

Private Member Functions

void configure (const Options &opt)
 

Private Attributes

kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_
 
moveit::core::RobotModelPtr model_
 
rdf_loader::RDFLoaderPtr rdf_loader_
 

Detailed Description

Definition at line 80 of file robot_model_loader.h.

Constructor & Destructor Documentation

◆ RobotModelLoader() [1/2]

robot_model_loader::RobotModelLoader::RobotModelLoader ( const Options opt = Options())

Default constructor.

Definition at line 85 of file robot_model_loader.cpp.

◆ RobotModelLoader() [2/2]

robot_model_loader::RobotModelLoader::RobotModelLoader ( const std::string &  robot_description,
bool  load_kinematics_solvers = true 
)

Definition at line 78 of file robot_model_loader.cpp.

◆ ~RobotModelLoader()

robot_model_loader::RobotModelLoader::~RobotModelLoader ( )

Definition at line 90 of file robot_model_loader.cpp.

Member Function Documentation

◆ configure()

void robot_model_loader::RobotModelLoader::configure ( const Options opt)
private

Definition at line 120 of file robot_model_loader.cpp.

◆ getKinematicsPluginLoader()

const kinematics_plugin_loader::KinematicsPluginLoaderPtr& robot_model_loader::RobotModelLoader::getKinematicsPluginLoader ( ) const
inline

Get the kinematics solvers plugin loader.

Note
This instance needs to be kept in scope, otherwise kinematics solver plugins may get unloaded.

Definition at line 149 of file robot_model_loader.h.

◆ getModel()

const moveit::core::RobotModelPtr& robot_model_loader::RobotModelLoader::getModel ( ) const
inline

Get the constructed planning_models::RobotModel.

Definition at line 118 of file robot_model_loader.h.

◆ getRDFLoader()

const rdf_loader::RDFLoaderPtr& robot_model_loader::RobotModelLoader::getRDFLoader ( ) const
inline

Get the instance of rdf_loader::RDFLoader that was used to load the robot description.

Definition at line 142 of file robot_model_loader.h.

◆ getRobotDescription()

const std::string& robot_model_loader::RobotModelLoader::getRobotDescription ( ) const
inline

Get the resolved parameter name for the robot description.

Definition at line 124 of file robot_model_loader.h.

◆ getSRDF()

const srdf::ModelSharedPtr& robot_model_loader::RobotModelLoader::getSRDF ( ) const
inline

Get the parsed SRDF model.

Definition at line 136 of file robot_model_loader.h.

◆ getURDF()

const urdf::ModelInterfaceSharedPtr& robot_model_loader::RobotModelLoader::getURDF ( ) const
inline

Get the parsed URDF model.

Definition at line 130 of file robot_model_loader.h.

◆ loadKinematicsSolvers()

void robot_model_loader::RobotModelLoader::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 explicitly by the options passed to the constructor.

Definition at line 201 of file robot_model_loader.cpp.

Member Data Documentation

◆ kinematics_loader_

kinematics_plugin_loader::KinematicsPluginLoaderPtr robot_model_loader::RobotModelLoader::kinematics_loader_
private

Definition at line 164 of file robot_model_loader.h.

◆ model_

moveit::core::RobotModelPtr robot_model_loader::RobotModelLoader::model_
private

Definition at line 162 of file robot_model_loader.h.

◆ rdf_loader_

rdf_loader::RDFLoaderPtr robot_model_loader::RobotModelLoader::rdf_loader_
private

Definition at line 163 of file robot_model_loader.h.


The documentation for this class was generated from the following files:


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