#include <urdf2gazebo.h>
Public Member Functions | |
void | addCollision (boost::shared_ptr< urdf::Link > link, std::string group_name, boost::shared_ptr< urdf::Collision > collision) |
void | addKeyValue (TiXmlElement *elem, const std::string &key, const std::string &value) |
void | addTransform (TiXmlElement *elem, const ::gazebo::math::Pose &transform) |
void | addVisual (boost::shared_ptr< urdf::Link > link, std::string group_name, boost::shared_ptr< urdf::Visual > visual) |
bool | 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 gazebo::math::Pose &transform, bool enforce_limits, bool reduce_fixed_joints) |
gazebo::math::Pose | copyPose (urdf::Pose pose) |
urdf::Pose | copyPose (gazebo::math::Pose pose) |
void | createBody (TiXmlElement *root, boost::shared_ptr< const urdf::Link > link, gazebo::math::Pose ¤tTransform, bool enforce_limits, bool reduce_fixed_joints) |
void | createGeom (TiXmlElement *elem, boost::shared_ptr< const urdf::Link > link, 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, gazebo::math::Pose ¤tTransform, bool enforce_limits, bool reduce_fixed_joints) |
void | createVisual (TiXmlElement *geom, boost::shared_ptr< const urdf::Link > link, 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) |
gazebo::math::Pose | inverseTransformToParentFrame (gazebo::math::Pose transform_in_link_frame, urdf::Pose parent_to_link_transform) |
void | listGazeboExtensions () |
void | listGazeboExtensions (std::string reference) |
void | parseGazeboExtension (TiXmlDocument &urdf_in) |
urdf::Vector3 | parseVector3 (TiXmlNode *key, double scale=1.0) |
void | printCollisionGroups (boost::shared_ptr< urdf::Link > link) |
void | printMass (boost::shared_ptr< urdf::Link > link) |
void | printMass (std::string link_name, dMass mass) |
void | reduceFixedJoints (TiXmlElement *root, boost::shared_ptr< urdf::Link > link) |
void | reduceGazeboExtensionToParent (boost::shared_ptr< urdf::Link > link) |
urdf::Pose | transformToParentFrame (urdf::Pose transform_in_link_frame, urdf::Pose parent_to_link_transform) |
returns the same transform in parent frame | |
gazebo::math::Pose | transformToParentFrame (gazebo::math::Pose transform_in_link_frame, urdf::Pose parent_to_link_transform) |
gazebo::math::Pose | transformToParentFrame (gazebo::math::Pose transform_in_link_frame, gazebo::math::Pose parent_to_link_transform) |
void | updateGazeboExtensionBlobsReductionTransform (GazeboExtension *ge) |
void | updateGazeboExtensionFrameReplace (GazeboExtension *ge, boost::shared_ptr< urdf::Link > link, 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 185 of file urdf2gazebo.h.
Definition at line 50 of file urdf2gazebo.cpp.
Definition at line 79 of file urdf2gazebo.cpp.
void URDF2Gazebo::addCollision | ( | boost::shared_ptr< urdf::Link > | link, |
std::string | group_name, | ||
boost::shared_ptr< urdf::Collision > | collision | ||
) |
Definition at line 166 of file urdf2gazebo.cpp.
void URDF2Gazebo::addKeyValue | ( | TiXmlElement * | elem, |
const std::string & | key, | ||
const std::string & | value | ||
) |
Definition at line 213 of file urdf2gazebo.cpp.
void URDF2Gazebo::addTransform | ( | TiXmlElement * | elem, |
const ::gazebo::math::Pose & | transform | ||
) |
Definition at line 232 of file urdf2gazebo.cpp.
void URDF2Gazebo::addVisual | ( | boost::shared_ptr< urdf::Link > | link, |
std::string | group_name, | ||
boost::shared_ptr< urdf::Visual > | visual | ||
) |
Definition at line 144 of file urdf2gazebo.cpp.
bool 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 1889 of file urdf2gazebo.cpp.
void URDF2Gazebo::convertLink | ( | TiXmlElement * | root, |
boost::shared_ptr< const urdf::Link > | link, | ||
const gazebo::math::Pose & | transform, | ||
bool | enforce_limits, | ||
bool | reduce_fixed_joints | ||
) |
Definition at line 1437 of file urdf2gazebo.cpp.
Definition at line 1467 of file urdf2gazebo.cpp.
Definition at line 1479 of file urdf2gazebo.cpp.
void URDF2Gazebo::createBody | ( | TiXmlElement * | root, |
boost::shared_ptr< const urdf::Link > | link, | ||
gazebo::math::Pose & | currentTransform, | ||
bool | enforce_limits, | ||
bool | reduce_fixed_joints | ||
) |
Definition at line 1492 of file urdf2gazebo.cpp.
void URDF2Gazebo::createGeom | ( | TiXmlElement * | elem, |
boost::shared_ptr< const urdf::Link > | link, | ||
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("") |
||
) |
Definition at line 1694 of file urdf2gazebo.cpp.
void URDF2Gazebo::createJoint | ( | TiXmlElement * | root, |
boost::shared_ptr< const urdf::Link > | link, | ||
gazebo::math::Pose & | currentTransform, | ||
bool | enforce_limits, | ||
bool | reduce_fixed_joints | ||
) |
Definition at line 1595 of file urdf2gazebo.cpp.
void URDF2Gazebo::createVisual | ( | TiXmlElement * | geom, |
boost::shared_ptr< const urdf::Link > | link, | ||
std::string | collision_type, | ||
boost::shared_ptr< urdf::Collision > | collision, | ||
boost::shared_ptr< urdf::Visual > | visual, | ||
std::string | original_reference | ||
) |
Definition at line 1769 of file urdf2gazebo.cpp.
std::string URDF2Gazebo::getGazeboValue | ( | TiXmlElement * | elem | ) |
Definition at line 249 of file urdf2gazebo.cpp.
std::string URDF2Gazebo::getGeometryBoundingBox | ( | boost::shared_ptr< urdf::Geometry > | geometry, |
double * | sizeVals | ||
) |
Definition at line 669 of file urdf2gazebo.cpp.
std::string URDF2Gazebo::getGeometrySize | ( | boost::shared_ptr< urdf::Geometry > | geometry, |
int * | sizeCount, | ||
double * | sizeVals | ||
) |
Definition at line 613 of file urdf2gazebo.cpp.
void URDF2Gazebo::insertGazeboExtensionBody | ( | TiXmlElement * | elem, |
std::string | link_name | ||
) |
Definition at line 522 of file urdf2gazebo.cpp.
void URDF2Gazebo::insertGazeboExtensionGeom | ( | TiXmlElement * | elem, |
std::string | link_name | ||
) |
Definition at line 468 of file urdf2gazebo.cpp.
void URDF2Gazebo::insertGazeboExtensionJoint | ( | TiXmlElement * | elem, |
std::string | joint_name | ||
) |
Definition at line 556 of file urdf2gazebo.cpp.
void URDF2Gazebo::insertGazeboExtensionRobot | ( | TiXmlElement * | elem | ) |
Definition at line 585 of file urdf2gazebo.cpp.
void URDF2Gazebo::insertGazeboExtensionVisual | ( | TiXmlElement * | elem, |
std::string | link_name | ||
) |
Definition at line 505 of file urdf2gazebo.cpp.
gazebo::math::Pose URDF2Gazebo::inverseTransformToParentFrame | ( | gazebo::math::Pose | transform_in_link_frame, |
urdf::Pose | parent_to_link_transform | ||
) |
Definition at line 961 of file urdf2gazebo.cpp.
void URDF2Gazebo::listGazeboExtensions | ( | ) |
Definition at line 1392 of file urdf2gazebo.cpp.
void URDF2Gazebo::listGazeboExtensions | ( | std::string | reference | ) |
Definition at line 1415 of file urdf2gazebo.cpp.
void URDF2Gazebo::parseGazeboExtension | ( | TiXmlDocument & | urdf_in | ) |
Definition at line 263 of file urdf2gazebo.cpp.
urdf::Vector3 URDF2Gazebo::parseVector3 | ( | TiXmlNode * | key, |
double | scale = 1.0 |
||
) |
Definition at line 84 of file urdf2gazebo.cpp.
void URDF2Gazebo::printCollisionGroups | ( | boost::shared_ptr< urdf::Link > | link | ) |
Definition at line 921 of file urdf2gazebo.cpp.
void URDF2Gazebo::printMass | ( | boost::shared_ptr< urdf::Link > | link | ) |
Definition at line 732 of file urdf2gazebo.cpp.
void URDF2Gazebo::printMass | ( | std::string | link_name, |
dMass | mass | ||
) |
Definition at line 722 of file urdf2gazebo.cpp.
void URDF2Gazebo::reduceFixedJoints | ( | TiXmlElement * | root, |
boost::shared_ptr< urdf::Link > | link | ||
) |
Definition at line 743 of file urdf2gazebo.cpp.
void URDF2Gazebo::reduceGazeboExtensionToParent | ( | boost::shared_ptr< urdf::Link > | link | ) |
Definition at line 980 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 934 of file urdf2gazebo.cpp.
gazebo::math::Pose URDF2Gazebo::transformToParentFrame | ( | gazebo::math::Pose | transform_in_link_frame, |
urdf::Pose | parent_to_link_transform | ||
) |
Definition at line 941 of file urdf2gazebo.cpp.
gazebo::math::Pose URDF2Gazebo::transformToParentFrame | ( | gazebo::math::Pose | transform_in_link_frame, |
gazebo::math::Pose | parent_to_link_transform | ||
) |
Definition at line 948 of file urdf2gazebo.cpp.
Definition at line 1305 of file urdf2gazebo.cpp.
void URDF2Gazebo::updateGazeboExtensionFrameReplace | ( | GazeboExtension * | ge, |
boost::shared_ptr< urdf::Link > | link, | ||
std::string | new_link_name | ||
) |
Definition at line 1041 of file urdf2gazebo.cpp.
std::string URDF2Gazebo::values2str | ( | unsigned int | count, |
const double * | values, | ||
double(*)(double) | conv = NULL |
||
) |
Definition at line 201 of file urdf2gazebo.cpp.
std::string URDF2Gazebo::vector32str | ( | const urdf::Vector3 | vector, |
double(*)(double) | conv = NULL |
||
) |
Definition at line 190 of file urdf2gazebo.cpp.
void URDF2Gazebo::walkChildAddNamespace | ( | TiXmlNode * | robot_xml, |
std::string | robot_namespace | ||
) |
Definition at line 1865 of file urdf2gazebo.cpp.
std::map<std::string, std::vector<GazeboExtension*> > urdf2gazebo::URDF2Gazebo::gazebo_extensions_ |
Definition at line 251 of file urdf2gazebo.h.