Go to the documentation of this file.
54 Options(
const std::string& robot_description =
"robot_description")
59 Options(
const std::string& urdf_string,
const std::string& srdf_string)
81 RobotModelLoader(
const std::string& robot_description,
bool load_kinematics_solvers =
true);
86 const moveit::core::RobotModelPtr&
getModel()
const
98 const urdf::ModelInterfaceSharedPtr&
getURDF()
const
125 kinematics_plugin_loader::KinematicsPluginLoaderPtr());
moveit::core::RobotModelPtr model_
const std::string & getRobotDescription() const
Get the resolved parameter name for the robot description.
const srdf::ModelSharedPtr & getSRDF() const
Get the parsed SRDF model.
rdf_loader::RDFLoaderPtr rdf_loader_
const kinematics_plugin_loader::KinematicsPluginLoaderPtr & getKinematicsPluginLoader() const
Get the kinematics solvers plugin loader.
std::shared_ptr< Model > ModelSharedPtr
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...
void configure(const Options &opt)
Structure that encodes the options to be passed to the RobotModelLoader constructor.
RobotModelLoader(const Options &opt=Options())
Default constructor.
const rdf_loader::RDFLoaderPtr & getRDFLoader() const
Get the instance of rdf_loader::RDFLoader that was used to load the robot description.
std::string robot_description_
The string name corresponding to the ROS param where the URDF is loaded; Using the same parameter nam...
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...
MOVEIT_CLASS_FORWARD(RobotModelLoader)
kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_
Options(const std::string &robot_description="robot_description")
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
const moveit::core::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
planning
Author(s): Ioan Sucan
, Sachin Chitta
autogenerated on Thu Nov 21 2024 03:24:18