37 #ifndef MOVEIT_PLANNING_MODELS_LOADER_ROBOT_MODEL_LOADER_ 38 #define MOVEIT_PLANNING_MODELS_LOADER_ROBOT_MODEL_LOADER_ 56 Options(
const std::string& robot_description =
"robot_description")
61 Options(
const std::string& urdf_string,
const std::string& srdf_string)
70 Options(TiXmlDocument* urdf_doc, TiXmlDocument* srdf_doc)
95 RobotModelLoader(
const std::string& robot_description,
bool load_kinematics_solvers =
true);
112 const urdf::ModelInterfaceSharedPtr&
getURDF()
const 139 kinematics_plugin_loader::KinematicsPluginLoaderPtr());
const srdf::ModelSharedPtr & getSRDF() const
Get the parsed SRDF 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...
TiXmlDocument * urdf_doc_
The parsed XML content of the URDF and SRDF documents.
const rdf_loader::RDFLoaderPtr & getRDFLoader() const
Get the instance of rdf_loader::RDFLoader that was used to load the robot description.
Options(const std::string &robot_description="robot_description")
Options(TiXmlDocument *urdf_doc, TiXmlDocument *srdf_doc)
kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_
std::string robot_description_
The string name corresponding to the ROS param where the URDF is loaded; Using the same parameter nam...
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.
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
rdf_loader::RDFLoaderPtr rdf_loader_
robot_model::RobotModelPtr model_
RobotModelLoader(const Options &opt=Options())
Default constructor.
TiXmlDocument * srdf_doc_
Options(const std::string &urdf_string, const std::string &srdf_string)
const std::string & getRobotDescription() const
Get the resolved parameter name for the robot description.
const robot_model::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
std::string urdf_string_
The string content of the URDF and SRDF documents. Loading from string is attempted only if loading f...
MOVEIT_CLASS_FORWARD(RobotModelLoader)
const kinematics_plugin_loader::KinematicsPluginLoaderPtr & getKinematicsPluginLoader() const
Get the kinematics solvers plugin loader.