82 RobotModelLoader(
const rclcpp::Node::SharedPtr& node,
const std::string& robot_description,
83 bool load_kinematics_solvers =
true);
88 const moveit::core::RobotModelPtr&
getModel()
const
96 return rdf_loader_->getRobotDescription();
100 const urdf::ModelInterfaceSharedPtr&
getURDF()
const
102 return rdf_loader_->getURDF();
108 return rdf_loader_->getSRDF();
121 return kinematics_loader_;
127 kinematics_plugin_loader::KinematicsPluginLoaderPtr());
130 void configure(
const Options& opt);
132 moveit::core::RobotModelPtr model_;
133 rdf_loader::RDFLoaderPtr rdf_loader_;
134 kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_;
135 const rclcpp::Node::SharedPtr node_;
136 rclcpp::Logger logger_;
#define MOVEIT_CLASS_FORWARD(C)
const srdf::ModelSharedPtr & getSRDF() const
Get the parsed SRDF model.
const kinematics_plugin_loader::KinematicsPluginLoaderPtr & getKinematicsPluginLoader() const
Get the kinematics solvers plugin loader.
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
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.
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...
const moveit::core::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
Structure that encodes the options to be passed to the RobotModelLoader constructor.
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...
Options(const std::string &robot_description="robot_description")
Options(const std::string &urdf_string, const std::string &srdf_string)
std::string urdf_string_
The string content of the URDF and SRDF documents. Loading from string is attempted only if loading f...