moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#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. | |
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. | |
const std::string & | getRobotDescription () const |
Get the resolved parameter name for the robot description. | |
const urdf::ModelInterfaceSharedPtr & | getURDF () const |
Get the parsed URDF model. | |
const srdf::ModelSharedPtr & | getSRDF () const |
Get the parsed SRDF model. | |
const rdf_loader::RDFLoaderPtr & | getRDFLoader () const |
Get the instance of rdf_loader::RDFLoader that was used to load the robot description. | |
const kinematics_plugin_loader::KinematicsPluginLoaderPtr & | getKinematicsPluginLoader () const |
Get the kinematics solvers plugin loader. | |
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. | |
Definition at line 49 of file robot_model_loader.h.
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.
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.
robot_model_loader::RobotModelLoader::~RobotModelLoader | ( | ) |
Definition at line 65 of file robot_model_loader.cpp.
|
inline |
Get the kinematics solvers plugin loader.
Definition at line 119 of file robot_model_loader.h.
|
inline |
Get the constructed planning_models::RobotModel.
Definition at line 88 of file robot_model_loader.h.
|
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.
|
inline |
Get the resolved parameter name for the robot description.
Definition at line 94 of file robot_model_loader.h.
|
inline |
Get the parsed SRDF model.
Definition at line 106 of file robot_model_loader.h.
|
inline |
Get the parsed URDF model.
Definition at line 100 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 256 of file robot_model_loader.cpp.