moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <rdf_loader.h>
Public Member Functions | |
RDFLoader (const std::shared_ptr< rclcpp::Node > &node, const std::string &ros_name="robot_description", bool default_continuous_value=false, double default_timeout=10.0) | |
Default constructor. | |
RDFLoader (const std::string &urdf_string, const std::string &srdf_string) | |
Initialize the robot model from a string representation of the URDF and SRDF documents. | |
const std::string & | getRobotDescription () const |
Get the resolved parameter name for the robot description. | |
const std::string & | getURDFString () const |
Get the URDF string. | |
const urdf::ModelInterfaceSharedPtr & | getURDF () const |
Get the parsed URDF model. | |
const srdf::ModelSharedPtr & | getSRDF () const |
Get the parsed SRDF model. | |
void | setNewModelCallback (const NewModelCallback &cb) |
Static Public Member Functions | |
static bool | isXacroFile (const std::string &path) |
determine if given path points to a xacro file | |
static bool | loadFileToString (std::string &buffer, const std::string &path) |
load file from given path into buffer | |
static bool | loadXacroFileToString (std::string &buffer, const std::string &path, const std::vector< std::string > &xacro_args) |
run xacro with the given args on the file, return result in buffer | |
static bool | loadXmlFileToString (std::string &buffer, const std::string &path, const std::vector< std::string > &xacro_args) |
helper that branches between loadFileToString() and loadXacroFileToString() based on result of isXacroFile() | |
static bool | loadPkgFileToString (std::string &buffer, const std::string &package_name, const std::string &relative_path, const std::vector< std::string > &xacro_args) |
helper that generates a file path based on package name and relative file path to package | |
Definition at line 57 of file rdf_loader.h.
rdf_loader::RDFLoader::RDFLoader | ( | const std::shared_ptr< rclcpp::Node > & | node, |
const std::string & | ros_name = "robot_description" , |
||
bool | default_continuous_value = false , |
||
double | default_timeout = 10.0 |
||
) |
Default constructor.
Loads the URDF from a parameter given by the string argument, and the SRDF that has the same name + the "_semantic" suffix
If the parameter does not exist, attempt to subscribe to topics with the same name and type std_msgs::msg::String.
(specifying default_continuous_value/default_timeout allows users to specify values without setting ros parameters)
node | ROS interface for parameters / topics |
ros_name | The string name corresponding to the URDF |
default_continuous_value | Default value for parameter with "_continuous" suffix. |
default_timeout | Default value for parameter with "_timeout" suffix. |
Definition at line 67 of file rdf_loader.cpp.
rdf_loader::RDFLoader::RDFLoader | ( | const std::string & | urdf_string, |
const std::string & | srdf_string | ||
) |
Initialize the robot model from a string representation of the URDF and SRDF documents.
Definition at line 90 of file rdf_loader.cpp.
|
inline |
Get the resolved parameter name for the robot description.
Definition at line 83 of file rdf_loader.h.
|
inline |
Get the parsed SRDF model.
Definition at line 101 of file rdf_loader.h.
|
inline |
Get the parsed URDF model.
Definition at line 95 of file rdf_loader.h.
|
inline |
Get the URDF string.
Definition at line 89 of file rdf_loader.h.
|
static |
determine if given path points to a xacro file
Definition at line 120 of file rdf_loader.cpp.
|
static |
load file from given path into buffer
Definition at line 128 of file rdf_loader.cpp.
|
static |
helper that generates a file path based on package name and relative file path to package
Definition at line 217 of file rdf_loader.cpp.
|
static |
run xacro with the given args on the file, return result in buffer
Definition at line 159 of file rdf_loader.cpp.
|
static |
helper that branches between loadFileToString() and loadXacroFileToString() based on result of isXacroFile()
Definition at line 206 of file rdf_loader.cpp.
|
inline |
Definition at line 106 of file rdf_loader.h.