#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. | |
const robot_model::RobotModelPtr & | getModel () const |
Get the constructed planning_models::RobotModel. | |
const rdf_loader::RDFLoaderPtr & | getRDFLoader () const |
Get the instance of rdf_loader::RDFLoader that was used to load the robot description. | |
const std::string & | getRobotDescription () const |
Get the resolved parameter name for the robot description. | |
const boost::shared_ptr < srdf::Model > & | getSRDF () const |
Get the parsed SRDF model. | |
const boost::shared_ptr < urdf::ModelInterface > & | 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 explicitly by the options passed to the constructor. | |
RobotModelLoader (const Options &opt=Options()) | |
Default constructor. | |
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_ |
robot_model::RobotModelPtr | model_ |
rdf_loader::RDFLoaderPtr | rdf_loader_ |
Definition at line 48 of file robot_model_loader.h.
robot_model_loader::RobotModelLoader::RobotModelLoader | ( | const Options & | opt = Options() | ) |
Default constructor.
Definition at line 49 of file robot_model_loader.cpp.
robot_model_loader::RobotModelLoader::RobotModelLoader | ( | const std::string & | robot_description, |
bool | load_kinematics_solvers = true |
||
) |
Definition at line 42 of file robot_model_loader.cpp.
Definition at line 54 of file robot_model_loader.cpp.
void robot_model_loader::RobotModelLoader::configure | ( | const Options & | opt | ) | [private] |
Definition at line 82 of file robot_model_loader.cpp.
const kinematics_plugin_loader::KinematicsPluginLoaderPtr& robot_model_loader::RobotModelLoader::getKinematicsPluginLoader | ( | ) | const [inline] |
Get the kinematics solvers plugin loader.
Definition at line 134 of file robot_model_loader.h.
const robot_model::RobotModelPtr& robot_model_loader::RobotModelLoader::getModel | ( | ) | const [inline] |
Get the constructed planning_models::RobotModel.
Definition at line 103 of file robot_model_loader.h.
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 127 of file robot_model_loader.h.
const std::string& robot_model_loader::RobotModelLoader::getRobotDescription | ( | ) | const [inline] |
Get the resolved parameter name for the robot description.
Definition at line 109 of file robot_model_loader.h.
const boost::shared_ptr<srdf::Model>& robot_model_loader::RobotModelLoader::getSRDF | ( | ) | const [inline] |
Get the parsed SRDF model.
Definition at line 121 of file robot_model_loader.h.
const boost::shared_ptr<urdf::ModelInterface>& robot_model_loader::RobotModelLoader::getURDF | ( | ) | const [inline] |
Get the parsed URDF model.
Definition at line 115 of file robot_model_loader.h.
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 164 of file robot_model_loader.cpp.
kinematics_plugin_loader::KinematicsPluginLoaderPtr robot_model_loader::RobotModelLoader::kinematics_loader_ [private] |
Definition at line 148 of file robot_model_loader.h.
robot_model::RobotModelPtr robot_model_loader::RobotModelLoader::model_ [private] |
Definition at line 146 of file robot_model_loader.h.
Definition at line 147 of file robot_model_loader.h.