Go to the documentation of this file.
54 RDFLoader(
const std::string& robot_description =
"robot_description");
57 RDFLoader(
const std::string& urdf_string,
const std::string& srdf_string);
66 const urdf::ModelInterfaceSharedPtr&
getURDF()
const
85 const std::vector<std::string>& xacro_args);
90 const std::vector<std::string>& xacro_args);
94 const std::string& relative_path,
const std::vector<std::string>& xacro_args);
99 urdf::ModelInterfaceSharedPtr
urdf_;
static bool loadFileToString(std::string &buffer, const std::string &path)
load file from given path into buffer
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
srdf::ModelSharedPtr srdf_
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
std::shared_ptr< Model > ModelSharedPtr
const srdf::ModelSharedPtr & getSRDF() const
Get the parsed SRDF model.
urdf::ModelInterfaceSharedPtr urdf_
MOVEIT_CLASS_FORWARD(RDFLoader)
static bool isXacroFile(const std::string &path)
determine if given path points to a xacro file
const std::string & getRobotDescription() const
Get the resolved parameter name for the robot description.
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
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 isXacr...
RDFLoader(const std::string &robot_description="robot_description")
Default constructor.
std::string robot_description_
planning
Author(s): Ioan Sucan
, Sachin Chitta
autogenerated on Sat Dec 21 2024 03:24:18