Default constructor.
More...
#include <rdf_loader.h>
|
const std::string & | getRobotDescription () const |
| Get the resolved parameter name for the robot description. More...
|
|
const srdf::ModelSharedPtr & | getSRDF () const |
| Get the parsed SRDF model. More...
|
|
const urdf::ModelInterfaceSharedPtr & | getURDF () const |
| Get the parsed URDF model. More...
|
|
| RDFLoader (const std::string &robot_description="robot_description") |
| Default constructor. More...
|
|
| 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. More...
|
|
| RDFLoader (TiXmlDocument *urdf_doc, TiXmlDocument *srdf_doc) |
| Initialize the robot model from a parsed XML representation of the URDF and SRDF. More...
|
|
|
static bool | isXacroFile (const std::string &path) |
| determine if given path points to a xacro file More...
|
|
static bool | loadFileToString (std::string &buffer, const std::string &path) |
| load file from given path into buffer More...
|
|
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 More...
|
|
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 More...
|
|
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() More...
|
|
Default constructor.
- Parameters
-
robot_description | The string name corresponding to the ROS param where the URDF is loaded |
Definition at line 53 of file rdf_loader.h.
rdf_loader::RDFLoader::RDFLoader |
( |
const std::string & |
robot_description = "robot_description" | ) |
|
Default constructor.
- Parameters
-
robot_description | The string name corresponding to the ROS param where the URDF is loaded; the SRDF is assumed to be at the same param name + the "_semantic" suffix |
Definition at line 53 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 96 of file rdf_loader.cpp.
rdf_loader::RDFLoader::RDFLoader |
( |
TiXmlDocument * |
urdf_doc, |
|
|
TiXmlDocument * |
srdf_doc |
|
) |
| |
Initialize the robot model from a parsed XML representation of the URDF and SRDF.
Definition at line 119 of file rdf_loader.cpp.
const std::string& rdf_loader::RDFLoader::getRobotDescription |
( |
| ) |
const |
|
inline |
Get the resolved parameter name for the robot description.
Definition at line 68 of file rdf_loader.h.
Get the parsed SRDF model.
Definition at line 80 of file rdf_loader.h.
const urdf::ModelInterfaceSharedPtr& rdf_loader::RDFLoader::getURDF |
( |
| ) |
const |
|
inline |
Get the parsed URDF model.
Definition at line 74 of file rdf_loader.h.
bool rdf_loader::RDFLoader::isXacroFile |
( |
const std::string & |
path | ) |
|
|
static |
determine if given path points to a xacro file
Definition at line 142 of file rdf_loader.cpp.
bool rdf_loader::RDFLoader::loadFileToString |
( |
std::string & |
buffer, |
|
|
const std::string & |
path |
|
) |
| |
|
static |
bool rdf_loader::RDFLoader::loadPkgFileToString |
( |
std::string & |
buffer, |
|
|
const std::string & |
package_name, |
|
|
const std::string & |
relative_path, |
|
|
const std::vector< std::string > & |
xacro_args |
|
) |
| |
|
static |
helper that generates a file path based on package name and relative file path to package
Definition at line 230 of file rdf_loader.cpp.
bool rdf_loader::RDFLoader::loadXacroFileToString |
( |
std::string & |
buffer, |
|
|
const std::string & |
path, |
|
|
const std::vector< std::string > & |
xacro_args |
|
) |
| |
|
static |
run xacro with the given args on the file, return result in buffer
Definition at line 181 of file rdf_loader.cpp.
bool rdf_loader::RDFLoader::loadXmlFileToString |
( |
std::string & |
buffer, |
|
|
const std::string & |
path, |
|
|
const std::vector< std::string > & |
xacro_args |
|
) |
| |
|
static |
std::string rdf_loader::RDFLoader::robot_description_ |
|
private |
urdf::ModelInterfaceSharedPtr rdf_loader::RDFLoader::urdf_ |
|
private |
The documentation for this class was generated from the following files: