#include <parser_urdf.hh>
Public Member Functions | |
URDF2Gazebo () | |
~URDF2Gazebo () | |
void | addKeyValue (TiXmlElement *elem, const std::string &key, const std::string &value) |
append key value pair to the end of the xml element | |
void | addTransform (TiXmlElement *elem, const ::gazebo::math::Pose &transform) |
append transform (pose) to the end of the xml element | |
gazebo::math::Pose | copyPose (urdf::Pose pose) |
reduced fixed joints: utility to copy between urdf::Pose and math::Pose | |
urdf::Pose | copyPose (gazebo::math::Pose pose) |
reduced fixed joints: utility to copy between urdf::Pose and math::Pose | |
void | createCollision (TiXmlElement *elem, const urdf::Link *link, urdf::Collision *collision, std::string old_link_name=std::string("")) |
create SDF Collision block based on URDF | |
void | createCollisions (TiXmlElement *elem, const urdf::Link *link) |
create collision blocks from urdf collisions | |
void | createGeometry (TiXmlElement *elem, urdf::Geometry *geometry) |
create SDF geometry block based on URDF | |
void | createInertial (TiXmlElement *elem, const urdf::Link *link) |
create SDF Inertial block based on URDF | |
void | createJoint (TiXmlElement *root, const urdf::Link *link, gazebo::math::Pose ¤tTransform) |
create SDF Joint block based on URDF | |
void | createLink (TiXmlElement *root, const urdf::Link *link, gazebo::math::Pose ¤tTransform) |
create SDF Link block based on URDF | |
void | createSDF (TiXmlElement *root, const urdf::Link *link, const gazebo::math::Pose &transform) |
create SDF from URDF link | |
void | createVisual (TiXmlElement *elem, const urdf::Link *link, urdf::Visual *visual, std::string old_link_name=std::string("")) |
create SDF Visual block based on URDF | |
void | createVisuals (TiXmlElement *elem, const urdf::Link *link) |
create visual blocks from urdf visuals | |
std::string | getGeometryBoundingBox (urdf::Geometry *geometry, double *sizeVals) |
std::string | getKeyValueAsString (TiXmlElement *elem) |
get value from <key value="..."> pair and return it as string | |
TiXmlDocument | initModelDoc (TiXmlDocument *_xmlDoc) |
TiXmlDocument | initModelFile (std::string filename) |
TiXmlDocument | initModelString (std::string urdf_str) |
TiXmlDocument | initModelString (std::string urdf_str, bool _enforce_limits) |
void | insertGazeboExtensionCollision (TiXmlElement *elem, std::string link_name) |
insert extensions into collision geoms | |
void | insertGazeboExtensionJoint (TiXmlElement *elem, std::string joint_name) |
insert extensions into joints | |
void | insertGazeboExtensionLink (TiXmlElement *elem, std::string link_name) |
insert extensions into links | |
void | insertGazeboExtensionRobot (TiXmlElement *elem) |
insert extensions into model | |
void | insertGazeboExtensionVisual (TiXmlElement *elem, std::string link_name) |
insert extensions into visuals | |
gazebo::math::Pose | inverseTransformToParentFrame (gazebo::math::Pose transform_in_link_frame, urdf::Pose parent_to_link_transform) |
reduced fixed joints: transform to parent frame | |
void | listGazeboExtensions () |
list extensions for debugging | |
void | listGazeboExtensions (std::string reference) |
list extensions for debugging | |
void | parseGazeboExtension (TiXmlDocument &urdf_xml) |
things that do not belong in urdf but should be mapped into sdf | |
urdf::Vector3 | parseVector3 (TiXmlNode *key, double scale=1.0) |
parser xml for vector 3 | |
void | printCollisionGroups (urdf::Link *link) |
print collision groups for debugging purposes | |
void | printMass (urdf::Link *link) |
print mass for link for debugging | |
void | printMass (std::string link_name, dMass mass) |
print mass for link for debugging | |
void | reduceCollisionsToParent (urdf::Link *link) |
reduce fixed joints: lump collisions to parent link | |
void | reduceCollisionToParent (urdf::Link *link, std::string group_name, urdf::Collision *collision) |
reduce fixed joints: lump collision when reducing fixed joints | |
void | reduceFixedJoints (TiXmlElement *root, urdf::Link *link) |
reduce fixed joints by lumping inertial, visual and | |
void | reduceGazeboExtensionContactSensorFrameReplace (std::vector< TiXmlElement * >::iterator blob_it, urdf::Link *link) |
reduced fixed joints: apply appropriate frame updates in urdf extensions when doing fixed joint reduction | |
void | reduceGazeboExtensionFrameReplace (GazeboExtension *ge, urdf::Link *link) |
reduced fixed joints: apply appropriate frame updates in urdf extensions when doing fixed joint reduction | |
void | reduceGazeboExtensionGripperFrameReplace (std::vector< TiXmlElement * >::iterator blob_it, urdf::Link *link) |
reduced fixed joints: apply appropriate frame updates in gripper inside urdf extensions when doing fixed joint reduction | |
void | reduceGazeboExtensionJointFrameReplace (std::vector< TiXmlElement * >::iterator blob_it, urdf::Link *link) |
reduced fixed joints: apply appropriate frame updates in joint inside urdf extensions when doing fixed joint reduction | |
void | reduceGazeboExtensionPluginFrameReplace (std::vector< TiXmlElement * >::iterator blob_it, urdf::Link *link, std::string plugin_name, std::string element_name, gazebo::math::Pose reduction_transform) |
reduced fixed joints: apply appropriate frame updates in plugins inside urdf extensions when doing fixed joint reduction | |
void | reduceGazeboExtensionProjectorFrameReplace (std::vector< TiXmlElement * >::iterator blob_it, urdf::Link *link) |
reduced fixed joints: apply appropriate frame updates in projector inside urdf extensions when doing fixed joint reduction | |
void | reduceGazeboExtensionProjectorTransformReduction (std::vector< TiXmlElement * >::iterator blob_it, gazebo::math::Pose reduction_transform) |
reduced fixed joints: apply transform reduction for projectors in extensions when doing fixed joint reduction | |
void | reduceGazeboExtensionSensorTransformReduction (std::vector< TiXmlElement * >::iterator blob_it, gazebo::math::Pose reduction_transform) |
reduced fixed joints: apply transform reduction for ray sensors in extensions when doing fixed joint reduction | |
void | reduceGazeboExtensionsTransformReduction (GazeboExtension *ge) |
reduced fixed joints: apply transform reduction to extensions when doing fixed joint reduction | |
void | reduceGazeboExtensionToParent (urdf::Link *link) |
reduced fixed joints: apply appropriate updates to urdf extensions when doing fixed joint reduction | |
void | reduceInertialToParent (urdf::Link *link) |
reduce fixed joints: lump inertial to parent link | |
void | reduceJointsToParent (urdf::Link *link) |
reduce fixed joints: lump joints to parent link | |
void | reduceVisualsToParent (urdf::Link *link) |
reduce fixed joints: lump visuals to parent link | |
void | reduceVisualToParent (urdf::Link *link, std::string group_name, urdf::Visual *visual) |
reduce fixed joints: lump visuals when reducing fixed joints | |
urdf::Pose | transformToParentFrame (urdf::Pose transform_in_link_frame, urdf::Pose parent_to_link_transform) |
reduced fixed joints: transform to parent frame | |
gazebo::math::Pose | transformToParentFrame (gazebo::math::Pose transform_in_link_frame, urdf::Pose parent_to_link_transform) |
reduced fixed joints: transform to parent frame | |
gazebo::math::Pose | transformToParentFrame (gazebo::math::Pose transform_in_link_frame, gazebo::math::Pose parent_to_link_transform) |
reduced fixed joints: transform to parent frame | |
std::string | values2str (unsigned int count, const double *values) |
convert values to string | |
std::string | vector32str (const urdf::Vector3 vector) |
convert Vector3 to string | |
Public Attributes | |
std::map< std::string, std::vector< GazeboExtension * > > | gazebo_extensions_ |
urdf2gazebo::URDF2Gazebo::URDF2Gazebo | ( | ) |
urdf2gazebo::URDF2Gazebo::~URDF2Gazebo | ( | ) |
void urdf2gazebo::URDF2Gazebo::addKeyValue | ( | TiXmlElement * | elem, |
const std::string & | key, | ||
const std::string & | value | ||
) |
append key value pair to the end of the xml element
void urdf2gazebo::URDF2Gazebo::addTransform | ( | TiXmlElement * | elem, |
const ::gazebo::math::Pose & | transform | ||
) |
append transform (pose) to the end of the xml element
gazebo::math::Pose urdf2gazebo::URDF2Gazebo::copyPose | ( | urdf::Pose | pose | ) |
reduced fixed joints: utility to copy between urdf::Pose and math::Pose
urdf::Pose urdf2gazebo::URDF2Gazebo::copyPose | ( | gazebo::math::Pose | pose | ) |
reduced fixed joints: utility to copy between urdf::Pose and math::Pose
void urdf2gazebo::URDF2Gazebo::createCollision | ( | TiXmlElement * | elem, |
const urdf::Link * | link, | ||
urdf::Collision * | collision, | ||
std::string | old_link_name = std::string("") |
||
) |
create SDF Collision block based on URDF
void urdf2gazebo::URDF2Gazebo::createCollisions | ( | TiXmlElement * | elem, |
const urdf::Link * | link | ||
) |
create collision blocks from urdf collisions
void urdf2gazebo::URDF2Gazebo::createGeometry | ( | TiXmlElement * | elem, |
urdf::Geometry * | geometry | ||
) |
create SDF geometry block based on URDF
void urdf2gazebo::URDF2Gazebo::createInertial | ( | TiXmlElement * | elem, |
const urdf::Link * | link | ||
) |
create SDF Inertial block based on URDF
void urdf2gazebo::URDF2Gazebo::createJoint | ( | TiXmlElement * | root, |
const urdf::Link * | link, | ||
gazebo::math::Pose & | currentTransform | ||
) |
create SDF Joint block based on URDF
void urdf2gazebo::URDF2Gazebo::createLink | ( | TiXmlElement * | root, |
const urdf::Link * | link, | ||
gazebo::math::Pose & | currentTransform | ||
) |
create SDF Link block based on URDF
void urdf2gazebo::URDF2Gazebo::createSDF | ( | TiXmlElement * | root, |
const urdf::Link * | link, | ||
const gazebo::math::Pose & | transform | ||
) |
create SDF from URDF link
void urdf2gazebo::URDF2Gazebo::createVisual | ( | TiXmlElement * | elem, |
const urdf::Link * | link, | ||
urdf::Visual * | visual, | ||
std::string | old_link_name = std::string("") |
||
) |
create SDF Visual block based on URDF
void urdf2gazebo::URDF2Gazebo::createVisuals | ( | TiXmlElement * | elem, |
const urdf::Link * | link | ||
) |
create visual blocks from urdf visuals
std::string urdf2gazebo::URDF2Gazebo::getGeometryBoundingBox | ( | urdf::Geometry * | geometry, |
double * | sizeVals | ||
) |
std::string urdf2gazebo::URDF2Gazebo::getKeyValueAsString | ( | TiXmlElement * | elem | ) |
get value from <key value="..."> pair and return it as string
TiXmlDocument urdf2gazebo::URDF2Gazebo::initModelDoc | ( | TiXmlDocument * | _xmlDoc | ) |
TiXmlDocument urdf2gazebo::URDF2Gazebo::initModelFile | ( | std::string | filename | ) |
TiXmlDocument urdf2gazebo::URDF2Gazebo::initModelString | ( | std::string | urdf_str | ) |
TiXmlDocument urdf2gazebo::URDF2Gazebo::initModelString | ( | std::string | urdf_str, |
bool | _enforce_limits | ||
) |
void urdf2gazebo::URDF2Gazebo::insertGazeboExtensionCollision | ( | TiXmlElement * | elem, |
std::string | link_name | ||
) |
insert extensions into collision geoms
void urdf2gazebo::URDF2Gazebo::insertGazeboExtensionJoint | ( | TiXmlElement * | elem, |
std::string | joint_name | ||
) |
insert extensions into joints
void urdf2gazebo::URDF2Gazebo::insertGazeboExtensionLink | ( | TiXmlElement * | elem, |
std::string | link_name | ||
) |
insert extensions into links
void urdf2gazebo::URDF2Gazebo::insertGazeboExtensionRobot | ( | TiXmlElement * | elem | ) |
insert extensions into model
void urdf2gazebo::URDF2Gazebo::insertGazeboExtensionVisual | ( | TiXmlElement * | elem, |
std::string | link_name | ||
) |
insert extensions into visuals
gazebo::math::Pose urdf2gazebo::URDF2Gazebo::inverseTransformToParentFrame | ( | gazebo::math::Pose | transform_in_link_frame, |
urdf::Pose | parent_to_link_transform | ||
) |
reduced fixed joints: transform to parent frame
void urdf2gazebo::URDF2Gazebo::listGazeboExtensions | ( | ) |
list extensions for debugging
void urdf2gazebo::URDF2Gazebo::listGazeboExtensions | ( | std::string | reference | ) |
list extensions for debugging
void urdf2gazebo::URDF2Gazebo::parseGazeboExtension | ( | TiXmlDocument & | urdf_xml | ) |
things that do not belong in urdf but should be mapped into sdf
urdf::Vector3 urdf2gazebo::URDF2Gazebo::parseVector3 | ( | TiXmlNode * | key, |
double | scale = 1.0 |
||
) |
parser xml for vector 3
void urdf2gazebo::URDF2Gazebo::printCollisionGroups | ( | urdf::Link * | link | ) |
print collision groups for debugging purposes
void urdf2gazebo::URDF2Gazebo::printMass | ( | urdf::Link * | link | ) |
print mass for link for debugging
void urdf2gazebo::URDF2Gazebo::printMass | ( | std::string | link_name, |
dMass | mass | ||
) |
print mass for link for debugging
void urdf2gazebo::URDF2Gazebo::reduceCollisionsToParent | ( | urdf::Link * | link | ) |
reduce fixed joints: lump collisions to parent link
void urdf2gazebo::URDF2Gazebo::reduceCollisionToParent | ( | urdf::Link * | link, |
std::string | group_name, | ||
urdf::Collision * | collision | ||
) |
reduce fixed joints: lump collision when reducing fixed joints
void urdf2gazebo::URDF2Gazebo::reduceFixedJoints | ( | TiXmlElement * | root, |
urdf::Link * | link | ||
) |
reduce fixed joints by lumping inertial, visual and
void urdf2gazebo::URDF2Gazebo::reduceGazeboExtensionContactSensorFrameReplace | ( | std::vector< TiXmlElement * >::iterator | blob_it, |
urdf::Link * | link | ||
) |
reduced fixed joints: apply appropriate frame updates in urdf extensions when doing fixed joint reduction
void urdf2gazebo::URDF2Gazebo::reduceGazeboExtensionFrameReplace | ( | GazeboExtension * | ge, |
urdf::Link * | link | ||
) |
reduced fixed joints: apply appropriate frame updates in urdf extensions when doing fixed joint reduction
void urdf2gazebo::URDF2Gazebo::reduceGazeboExtensionGripperFrameReplace | ( | std::vector< TiXmlElement * >::iterator | blob_it, |
urdf::Link * | link | ||
) |
reduced fixed joints: apply appropriate frame updates in gripper inside urdf extensions when doing fixed joint reduction
void urdf2gazebo::URDF2Gazebo::reduceGazeboExtensionJointFrameReplace | ( | std::vector< TiXmlElement * >::iterator | blob_it, |
urdf::Link * | link | ||
) |
reduced fixed joints: apply appropriate frame updates in joint inside urdf extensions when doing fixed joint reduction
void urdf2gazebo::URDF2Gazebo::reduceGazeboExtensionPluginFrameReplace | ( | std::vector< TiXmlElement * >::iterator | blob_it, |
urdf::Link * | link, | ||
std::string | plugin_name, | ||
std::string | element_name, | ||
gazebo::math::Pose | reduction_transform | ||
) |
reduced fixed joints: apply appropriate frame updates in plugins inside urdf extensions when doing fixed joint reduction
void urdf2gazebo::URDF2Gazebo::reduceGazeboExtensionProjectorFrameReplace | ( | std::vector< TiXmlElement * >::iterator | blob_it, |
urdf::Link * | link | ||
) |
reduced fixed joints: apply appropriate frame updates in projector inside urdf extensions when doing fixed joint reduction
void urdf2gazebo::URDF2Gazebo::reduceGazeboExtensionProjectorTransformReduction | ( | std::vector< TiXmlElement * >::iterator | blob_it, |
gazebo::math::Pose | reduction_transform | ||
) |
reduced fixed joints: apply transform reduction for projectors in extensions when doing fixed joint reduction
void urdf2gazebo::URDF2Gazebo::reduceGazeboExtensionSensorTransformReduction | ( | std::vector< TiXmlElement * >::iterator | blob_it, |
gazebo::math::Pose | reduction_transform | ||
) |
reduced fixed joints: apply transform reduction for ray sensors in extensions when doing fixed joint reduction
void urdf2gazebo::URDF2Gazebo::reduceGazeboExtensionsTransformReduction | ( | GazeboExtension * | ge | ) |
reduced fixed joints: apply transform reduction to extensions when doing fixed joint reduction
void urdf2gazebo::URDF2Gazebo::reduceGazeboExtensionToParent | ( | urdf::Link * | link | ) |
reduced fixed joints: apply appropriate updates to urdf extensions when doing fixed joint reduction
void urdf2gazebo::URDF2Gazebo::reduceInertialToParent | ( | urdf::Link * | link | ) |
reduce fixed joints: lump inertial to parent link
void urdf2gazebo::URDF2Gazebo::reduceJointsToParent | ( | urdf::Link * | link | ) |
reduce fixed joints: lump joints to parent link
void urdf2gazebo::URDF2Gazebo::reduceVisualsToParent | ( | urdf::Link * | link | ) |
reduce fixed joints: lump visuals to parent link
void urdf2gazebo::URDF2Gazebo::reduceVisualToParent | ( | urdf::Link * | link, |
std::string | group_name, | ||
urdf::Visual * | visual | ||
) |
reduce fixed joints: lump visuals when reducing fixed joints
urdf::Pose urdf2gazebo::URDF2Gazebo::transformToParentFrame | ( | urdf::Pose | transform_in_link_frame, |
urdf::Pose | parent_to_link_transform | ||
) |
reduced fixed joints: transform to parent frame
gazebo::math::Pose urdf2gazebo::URDF2Gazebo::transformToParentFrame | ( | gazebo::math::Pose | transform_in_link_frame, |
urdf::Pose | parent_to_link_transform | ||
) |
reduced fixed joints: transform to parent frame
gazebo::math::Pose urdf2gazebo::URDF2Gazebo::transformToParentFrame | ( | gazebo::math::Pose | transform_in_link_frame, |
gazebo::math::Pose | parent_to_link_transform | ||
) |
reduced fixed joints: transform to parent frame
std::string urdf2gazebo::URDF2Gazebo::values2str | ( | unsigned int | count, |
const double * | values | ||
) |
convert values to string
std::string urdf2gazebo::URDF2Gazebo::vector32str | ( | const urdf::Vector3 | vector | ) |
convert Vector3 to string
std::map<std::string, std::vector<GazeboExtension*> > urdf2gazebo::URDF2Gazebo::gazebo_extensions_ |