$search
#include <urdf2gazebo.h>
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, bool reduce_fixed_joints) |
void | createBody (TiXmlElement *root, boost::shared_ptr< const urdf::Link > link, const btTransform &transform, btTransform ¤tTransform, bool enforce_limits, bool reduce_fixed_joints) |
void | createGeom (TiXmlElement *root, TiXmlElement *elem, boost::shared_ptr< const urdf::Link > link, const btTransform &transform, btTransform ¤tTransform, std::string collision_type, boost::shared_ptr< urdf::Collision > collision, boost::shared_ptr< urdf::Visual > visual, int linkGeomSize, double linkSize[3], std::string original_reference=std::string("")) |
void | createJoint (TiXmlElement *root, boost::shared_ptr< const urdf::Link > link, btTransform ¤tTransform, bool enforce_limits, bool reduce_fixed_joints) |
void | createVisual (TiXmlElement *root, TiXmlElement *geom, boost::shared_ptr< const urdf::Link > link, const btTransform &transform, btTransform ¤tTransform, std::string collision_type, boost::shared_ptr< urdf::Collision > collision, boost::shared_ptr< urdf::Visual > visual, std::string original_reference) |
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 | listGazeboExtensions (std::string reference) |
void | listGazeboExtensions () |
void | parseGazeboExtension (TiXmlDocument &urdf_in) |
void | printMass (std::string link_name, dMass mass) |
void | printMass (boost::shared_ptr< urdf::Link > link) |
void | reduceGazeboExtensionToParent (boost::shared_ptr< urdf::Link > link) |
void | setupTransform (urdf::Pose &pose, btTransform transform) |
void | setupTransform (btTransform &transform, urdf::Pose pose) |
urdf::Pose | transformToParentFrame (urdf::Pose transform_in_link_frame, urdf::Pose parent_to_link_transform) |
returns the same transform in parent frame | |
void | updateGazeboExtensionBlobsReductionTransform (GazeboExtension *ext) |
void | updateGazeboExtensionFrameReplace (std::vector< TiXmlElement * > &blocks, std::string link_name, std::string new_link_name) |
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, std::vector< GazeboExtension * > > | gazebo_extensions_ |
Definition at line 151 of file urdf2gazebo.h.
URDF2Gazebo::URDF2Gazebo | ( | ) |
Definition at line 43 of file urdf2gazebo.cpp.
URDF2Gazebo::~URDF2Gazebo | ( | ) |
Definition at line 47 of file urdf2gazebo.cpp.
void URDF2Gazebo::addKeyValue | ( | TiXmlElement * | elem, | |
const std::string & | key, | |||
const std::string & | value | |||
) |
Definition at line 93 of file urdf2gazebo.cpp.
void URDF2Gazebo::addTransform | ( | TiXmlElement * | elem, | |
const ::btTransform & | transform | |||
) |
Definition at line 112 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 1569 of file urdf2gazebo.cpp.
void URDF2Gazebo::convertLink | ( | TiXmlElement * | root, | |
boost::shared_ptr< const urdf::Link > | link, | |||
const btTransform & | transform, | |||
bool | enforce_limits, | |||
bool | reduce_fixed_joints | |||
) |
Definition at line 1124 of file urdf2gazebo.cpp.
void URDF2Gazebo::createBody | ( | TiXmlElement * | root, | |
boost::shared_ptr< const urdf::Link > | link, | |||
const btTransform & | transform, | |||
btTransform & | currentTransform, | |||
bool | enforce_limits, | |||
bool | reduce_fixed_joints | |||
) |
Definition at line 1154 of file urdf2gazebo.cpp.
void urdf2gazebo::URDF2Gazebo::createGeom | ( | TiXmlElement * | root, | |
TiXmlElement * | elem, | |||
boost::shared_ptr< const urdf::Link > | link, | |||
const btTransform & | transform, | |||
btTransform & | currentTransform, | |||
std::string | collision_type, | |||
boost::shared_ptr< urdf::Collision > | collision, | |||
boost::shared_ptr< urdf::Visual > | visual, | |||
int | linkGeomSize, | |||
double | linkSize[3], | |||
std::string | original_reference = std::string("") | |||
) |
void URDF2Gazebo::createJoint | ( | TiXmlElement * | root, | |
boost::shared_ptr< const urdf::Link > | link, | |||
btTransform & | currentTransform, | |||
bool | enforce_limits, | |||
bool | reduce_fixed_joints | |||
) |
Definition at line 1271 of file urdf2gazebo.cpp.
void URDF2Gazebo::createVisual | ( | TiXmlElement * | root, | |
TiXmlElement * | geom, | |||
boost::shared_ptr< const urdf::Link > | link, | |||
const btTransform & | transform, | |||
btTransform & | currentTransform, | |||
std::string | collision_type, | |||
boost::shared_ptr< urdf::Collision > | collision, | |||
boost::shared_ptr< urdf::Visual > | visual, | |||
std::string | original_reference | |||
) |
Definition at line 1447 of file urdf2gazebo.cpp.
std::string URDF2Gazebo::getGazeboValue | ( | TiXmlElement * | elem | ) |
Definition at line 133 of file urdf2gazebo.cpp.
std::string URDF2Gazebo::getGeometryBoundingBox | ( | boost::shared_ptr< urdf::Geometry > | geometry, | |
double * | sizeVals | |||
) |
Definition at line 553 of file urdf2gazebo.cpp.
std::string URDF2Gazebo::getGeometrySize | ( | boost::shared_ptr< urdf::Geometry > | geometry, | |
int * | sizeCount, | |||
double * | sizeVals | |||
) |
Definition at line 497 of file urdf2gazebo.cpp.
void URDF2Gazebo::insertGazeboExtensionBody | ( | TiXmlElement * | elem, | |
std::string | link_name | |||
) |
Definition at line 400 of file urdf2gazebo.cpp.
void URDF2Gazebo::insertGazeboExtensionGeom | ( | TiXmlElement * | elem, | |
std::string | link_name | |||
) |
Definition at line 352 of file urdf2gazebo.cpp.
void URDF2Gazebo::insertGazeboExtensionJoint | ( | TiXmlElement * | elem, | |
std::string | joint_name | |||
) |
Definition at line 440 of file urdf2gazebo.cpp.
void URDF2Gazebo::insertGazeboExtensionRobot | ( | TiXmlElement * | elem | ) |
Definition at line 469 of file urdf2gazebo.cpp.
void URDF2Gazebo::insertGazeboExtensionVisual | ( | TiXmlElement * | elem, | |
std::string | link_name | |||
) |
Definition at line 383 of file urdf2gazebo.cpp.
void URDF2Gazebo::listGazeboExtensions | ( | std::string | reference | ) |
Definition at line 1102 of file urdf2gazebo.cpp.
void URDF2Gazebo::listGazeboExtensions | ( | ) |
Definition at line 1079 of file urdf2gazebo.cpp.
void URDF2Gazebo::parseGazeboExtension | ( | TiXmlDocument & | urdf_in | ) |
Definition at line 147 of file urdf2gazebo.cpp.
void URDF2Gazebo::printMass | ( | std::string | link_name, | |
dMass | mass | |||
) |
Definition at line 606 of file urdf2gazebo.cpp.
void URDF2Gazebo::printMass | ( | boost::shared_ptr< urdf::Link > | link | ) |
Definition at line 616 of file urdf2gazebo.cpp.
void URDF2Gazebo::reduceGazeboExtensionToParent | ( | boost::shared_ptr< urdf::Link > | link | ) |
Definition at line 847 of file urdf2gazebo.cpp.
void URDF2Gazebo::setupTransform | ( | urdf::Pose & | pose, | |
btTransform | transform | |||
) |
Definition at line 82 of file urdf2gazebo.cpp.
void URDF2Gazebo::setupTransform | ( | btTransform & | transform, | |
urdf::Pose | pose | |||
) |
Definition at line 75 of file urdf2gazebo.cpp.
urdf::Pose URDF2Gazebo::transformToParentFrame | ( | urdf::Pose | transform_in_link_frame, | |
urdf::Pose | parent_to_link_transform | |||
) |
returns the same transform in parent frame
Definition at line 817 of file urdf2gazebo.cpp.
void URDF2Gazebo::updateGazeboExtensionBlobsReductionTransform | ( | GazeboExtension * | ext | ) |
Definition at line 1019 of file urdf2gazebo.cpp.
void URDF2Gazebo::updateGazeboExtensionFrameReplace | ( | std::vector< TiXmlElement * > & | blocks, | |
std::string | link_name, | |||
std::string | new_link_name | |||
) |
Definition at line 904 of file urdf2gazebo.cpp.
std::string URDF2Gazebo::values2str | ( | unsigned int | count, | |
const double * | values, | |||
double(*)(double) | conv = NULL | |||
) |
Definition at line 63 of file urdf2gazebo.cpp.
std::string URDF2Gazebo::vector32str | ( | const urdf::Vector3 | vector, | |
double(*)(double) | conv = NULL | |||
) |
Definition at line 52 of file urdf2gazebo.cpp.
void URDF2Gazebo::walkChildAddNamespace | ( | TiXmlNode * | robot_xml, | |
std::string | robot_namespace | |||
) |
Definition at line 1545 of file urdf2gazebo.cpp.
std::map<std::string, std::vector<GazeboExtension*> > urdf2gazebo::URDF2Gazebo::gazebo_extensions_ |
Definition at line 214 of file urdf2gazebo.h.