urdf2gazebo::URDF2Gazebo Class Reference

#include <urdf2gazebo.h>

List of all members.

Public Member Functions

void addKeyValue (TiXmlElement *elem, const std::string &key, const std::string &value)
void addTransform (TiXmlElement *elem, const ::btTransform &transform)
void convert (TiXmlDocument &urdf_in, TiXmlDocument &gazebo_xml_out, bool enforce_limits, urdf::Vector3 initial_xyz, urdf::Vector3 initial_rpy, std::string model_name=std::string(), std::string robot_namespace=std::string(), bool xml_declaration=false)
void convertLink (TiXmlElement *root, boost::shared_ptr< const urdf::Link > link, const btTransform &transform, bool enforce_limits)
std::string getGazeboValue (TiXmlElement *elem)
std::string getGeometryBoundingBox (boost::shared_ptr< urdf::Geometry > geometry, double *sizeVals)
std::string getGeometrySize (boost::shared_ptr< urdf::Geometry > geometry, int *sizeCount, double *sizeVals)
void insertGazeboExtensionBody (TiXmlElement *elem, std::string link_name)
void insertGazeboExtensionGeom (TiXmlElement *elem, std::string link_name)
void insertGazeboExtensionJoint (TiXmlElement *elem, std::string joint_name)
void insertGazeboExtensionRobot (TiXmlElement *elem)
void insertGazeboExtensionVisual (TiXmlElement *elem, std::string link_name)
void parseGazeboExtension (TiXmlDocument &urdf_in)
void setupTransform (btTransform &transform, urdf::Pose pose)
 URDF2Gazebo ()
std::string values2str (unsigned int count, const double *values, double(*conv)(double))
std::string vector32str (const urdf::Vector3 vector, double(*conv)(double))
void walkChildAddNamespace (TiXmlNode *robot_xml, std::string robot_namespace)
 ~URDF2Gazebo ()

Public Attributes

std::map< std::string,
GazeboExtension * > 
gazebo_extensions_

Detailed Description

Definition at line 107 of file urdf2gazebo.h.


Constructor & Destructor Documentation

URDF2Gazebo::URDF2Gazebo (  ) 

Definition at line 42 of file urdf2gazebo.cpp.

URDF2Gazebo::~URDF2Gazebo (  ) 

Definition at line 46 of file urdf2gazebo.cpp.


Member Function Documentation

void URDF2Gazebo::addKeyValue ( TiXmlElement *  elem,
const std::string &  key,
const std::string &  value 
)

Definition at line 80 of file urdf2gazebo.cpp.

void URDF2Gazebo::addTransform ( TiXmlElement *  elem,
const ::btTransform &  transform 
)

Definition at line 88 of file urdf2gazebo.cpp.

void URDF2Gazebo::convert ( TiXmlDocument &  urdf_in,
TiXmlDocument &  gazebo_xml_out,
bool  enforce_limits,
urdf::Vector3  initial_xyz,
urdf::Vector3  initial_rpy,
std::string  model_name = std::string(),
std::string  robot_namespace = std::string(),
bool  xml_declaration = false 
)

Definition at line 956 of file urdf2gazebo.cpp.

void URDF2Gazebo::convertLink ( TiXmlElement *  root,
boost::shared_ptr< const urdf::Link >  link,
const btTransform &  transform,
bool  enforce_limits 
)

Definition at line 543 of file urdf2gazebo.cpp.

std::string URDF2Gazebo::getGazeboValue ( TiXmlElement *  elem  ) 

Definition at line 109 of file urdf2gazebo.cpp.

std::string URDF2Gazebo::getGeometryBoundingBox ( boost::shared_ptr< urdf::Geometry >  geometry,
double *  sizeVals 
)

Definition at line 490 of file urdf2gazebo.cpp.

std::string URDF2Gazebo::getGeometrySize ( boost::shared_ptr< urdf::Geometry >  geometry,
int *  sizeCount,
double *  sizeVals 
)

Definition at line 434 of file urdf2gazebo.cpp.

void URDF2Gazebo::insertGazeboExtensionBody ( TiXmlElement *  elem,
std::string  link_name 
)

Definition at line 353 of file urdf2gazebo.cpp.

void URDF2Gazebo::insertGazeboExtensionGeom ( TiXmlElement *  elem,
std::string  link_name 
)

Definition at line 313 of file urdf2gazebo.cpp.

void URDF2Gazebo::insertGazeboExtensionJoint ( TiXmlElement *  elem,
std::string  joint_name 
)

Definition at line 383 of file urdf2gazebo.cpp.

void URDF2Gazebo::insertGazeboExtensionRobot ( TiXmlElement *  elem  ) 

Definition at line 409 of file urdf2gazebo.cpp.

void URDF2Gazebo::insertGazeboExtensionVisual ( TiXmlElement *  elem,
std::string  link_name 
)

Definition at line 339 of file urdf2gazebo.cpp.

void URDF2Gazebo::parseGazeboExtension ( TiXmlDocument &  urdf_in  ) 

Definition at line 123 of file urdf2gazebo.cpp.

void URDF2Gazebo::setupTransform ( btTransform &  transform,
urdf::Pose  pose 
)

Definition at line 73 of file urdf2gazebo.cpp.

std::string URDF2Gazebo::values2str ( unsigned int  count,
const double *  values,
double(*)(double)  conv = NULL 
)

Definition at line 61 of file urdf2gazebo.cpp.

std::string URDF2Gazebo::vector32str ( const urdf::Vector3  vector,
double(*)(double)  conv = NULL 
)

Definition at line 51 of file urdf2gazebo.cpp.

void URDF2Gazebo::walkChildAddNamespace ( TiXmlNode *  robot_xml,
std::string  robot_namespace 
)

Definition at line 932 of file urdf2gazebo.cpp.


Member Data Documentation

Definition at line 140 of file urdf2gazebo.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables


gazebo_tools
Author(s): John Hsu
autogenerated on Fri Jan 11 09:40:43 2013