moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | 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

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

Detailed Description

Definition at line 49 of file robot_model_loader.h.

Constructor & Destructor Documentation

◆ RobotModelLoader() [1/2]

robot_model_loader::RobotModelLoader::RobotModelLoader ( const rclcpp::Node::SharedPtr &  node,
const Options opt = Options() 
)

Default constructor.

Definition at line 59 of file robot_model_loader.cpp.

◆ RobotModelLoader() [2/2]

robot_model_loader::RobotModelLoader::RobotModelLoader ( const rclcpp::Node::SharedPtr &  node,
const std::string &  robot_description,
bool  load_kinematics_solvers = true 
)

Definition at line 50 of file robot_model_loader.cpp.

◆ ~RobotModelLoader()

robot_model_loader::RobotModelLoader::~RobotModelLoader ( )

Definition at line 64 of file robot_model_loader.cpp.

Member Function Documentation

◆ 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 119 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 88 of file robot_model_loader.h.

Here is the caller graph for this function:

◆ 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 112 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 94 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 106 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 100 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 251 of file robot_model_loader.cpp.

Here is the call graph for this function:

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