37 #ifndef MOVEIT_PLANNING_RDF_LOADER_ 38 #define MOVEIT_PLANNING_RDF_LOADER_ 59 RDFLoader(
const std::string& robot_description =
"robot_description");
62 RDFLoader(
const std::string& urdf_string,
const std::string& srdf_string);
65 RDFLoader(TiXmlDocument* urdf_doc, TiXmlDocument* srdf_doc);
74 const urdf::ModelInterfaceSharedPtr&
getURDF()
const 93 const std::vector<std::string>& xacro_args);
98 const std::vector<std::string>& xacro_args);
102 const std::string& relative_path,
const std::vector<std::string>& xacro_args);
107 urdf::ModelInterfaceSharedPtr
urdf_;
const srdf::ModelSharedPtr & getSRDF() const
Get the parsed SRDF model.
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 ...
static bool isXacroFile(const std::string &path)
determine if given path points to a xacro file
RDFLoader(const std::string &robot_description="robot_description")
Default constructor.
static bool loadFileToString(std::string &buffer, const std::string &path)
load file from given path into buffer
const std::string & getRobotDescription() const
Get the resolved parameter name for the robot description.
srdf::ModelSharedPtr srdf_
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...
urdf::ModelInterfaceSharedPtr urdf_
MOVEIT_CLASS_FORWARD(RDFLoader)
std::string robot_description_
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
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