Namespaces | Classes | Typedefs | Functions
urdf_traverser Namespace Reference

Namespaces

namespace  helpers

Classes

class  FactorRecursionParams
 Includes a factor value to be passed on in recursion. More...
class  FlagRecursionParams
 Includes a flag to be passed on in recursion. More...
class  LinkRecursionParams
 Can be used for all recursive functions which have a specific link as a result. A reference to the model is also included so that it can be used from within the callbacks. More...
class  ModelRecursionParams
 Recursion parameters including link to the underlying URDF model. The underlying urdf model can be used to add/remove links during traversal, and/or change the root link during or after traversal. More...
class  RecursionParams
 Base class for recursion parameters passed during traversal of a URDF tree. Encapsulates data carried within a recursion. At each recursion, the according fields link and level are set. Any subclass can add their own recursion parameters to pass through all recursions. A subclass of this type may for example be used to build the result of the traversal. More...
class  StringVectorRecursionParams
 Collects string values into a vector. More...
class  UrdfTraverser
 This class provides functions to traverse the URDF and provides convenience functions to access the URDF model. More...

Typedefs

typedef shr_lib::shared_ptr
< urdf::Box > 
BoxPtr
typedef shr_lib::shared_ptr
< urdf::Collision > 
CollisionPtr
typedef shr_lib::shared_ptr
< urdf::Cylinder > 
CylinderPtr
typedef Eigen::Transform
< double, 3, Eigen::Affine > 
EigenTransform
typedef FactorRecursionParams::Ptr FactorRecursionParamsPtr
typedef FlagRecursionParams::Ptr FlagRecursionParamsPtr
typedef shr_lib::shared_ptr
< urdf::Geometry > 
GeometryPtr
typedef shr_lib::shared_ptr
< urdf::Inertial > 
InertialPtr
typedef shr_lib::shared_ptr
< const urdf::Joint > 
JointConstPtr
typedef shr_lib::shared_ptr
< urdf::Joint > 
JointPtr
typedef shr_lib::shared_ptr
< const urdf::Link > 
LinkConstPtr
typedef shr_lib::shared_ptr
< urdf::Link > 
LinkPtr
typedef LinkRecursionParams::Ptr LinkRecursionParamsPtr
typedef shr_lib::shared_ptr
< urdf::Material > 
MaterialPtr
typedef shr_lib::shared_ptr
< urdf::Mesh > 
MeshPtr
typedef shr_lib::shared_ptr
< const urdf::Model
ModelConstPtr
typedef shr_lib::shared_ptr
< urdf::Model
ModelPtr
typedef ModelRecursionParams::Ptr ModelRecursionParamsPtr
typedef RecursionParams::Ptr RecursionParamsPtr
typedef shr_lib::shared_ptr
< urdf::Sphere > 
SpherePtr
typedef
StringVectorRecursionParams::Ptr 
StringVectorRecursionParamsPtr
typedef shr_lib::shared_ptr
< urdf::Visual > 
VisualPtr

Functions

bool applyTransform (JointPtr &joint, const EigenTransform &trans, bool preMult)
void applyTransform (LinkPtr &link, const EigenTransform &trans, bool preMult)
void applyTransform (const EigenTransform &t, urdf::Vector3 &v)
std::vector< JointPtrgetChain (const LinkConstPtr &from_link, const LinkConstPtr &to_link)
bool getDependencyOrderedJoints (urdf_traverser::UrdfTraverser &traverser, std::vector< JointPtr > &result, const JointPtr &fromJoint, bool allowSplits=true, bool onlyActive=true)
bool getDependencyOrderedJoints (urdf_traverser::UrdfTraverser &traverser, std::vector< JointPtr > &result, const std::string &fromLink, bool allowSplits=true, bool onlyActive=true)
bool getJointNames (UrdfTraverser &traverser, const std::string &fromLink, const bool skipFixed, std::vector< std::string > &result)
Eigen::Vector3d getRotationAxis (const JointConstPtr &j)
EigenTransform getTransform (const urdf::Pose &p)
EigenTransform getTransform (const JointConstPtr &joint)
EigenTransform getTransform (const LinkConstPtr &link)
EigenTransform getTransform (const LinkConstPtr &from_link, const LinkConstPtr &to_link)
Eigen::Matrix4d getTransformMatrix (const LinkConstPtr &from_link, const LinkConstPtr &to_link)
bool hasFixedJoints (UrdfTraverser &traverser, const std::string &fromLink)
bool isActive (const JointPtr &joint)
bool isChildJointOf (const LinkConstPtr &parent, const JointConstPtr &joint)
bool isChildOf (const LinkConstPtr &parent, const LinkConstPtr &child)
bool jointTransformForAxis (const JointConstPtr &joint, const Eigen::Vector3d &axis, Eigen::Quaterniond &rotation)
bool printModel (urdf_traverser::UrdfTraverser &traverser, const std::string &fromLink, bool verbose)
bool printModel (urdf_traverser::UrdfTraverser &traverser, bool verbose)
void scaleTranslation (EigenTransform &t, double scale_factor)
bool scaleTranslation (JointPtr &joint, double scale_factor)
void scaleTranslation (LinkPtr &link, double scale_factor)
void setTransform (const EigenTransform &t, urdf::Pose &p)
void setTransform (const EigenTransform &t, JointPtr &joint)

Detailed Description

<ORGANIZATION> = Jennifer Buehler <COPYRIGHT holder>=""> = Jennifer Buehler

Copyright (c) 2016 Jennifer Buehler All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the name of the <ORGANIZATION> nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT holder>=""> BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------------

<ORGANIZATION> = Jennifer Buehler <COPYRIGHT holder>=""> = Jennifer Buehler

Copyright (c) 2016 Jennifer Buehler All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the name of the <ORGANIZATION> nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT holder>=""> BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------------ Helper functions for operations on the urdf elements.

Author:
Jennifer Buehler
Date:
last edited October 2015

<ORGANIZATION> = Jennifer Buehler <COPYRIGHT holder>=""> = Jennifer Buehler

Copyright (c) 2016 Jennifer Buehler All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the name of the <ORGANIZATION> nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT holder>=""> BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------------ Helper functions for i/o operations.

Author:
Jennifer Buehler
Date:
last edited October 2015

Typedef Documentation

typedef shr_lib::shared_ptr<urdf::Box> urdf_traverser::BoxPtr

Definition at line 64 of file Types.h.

typedef shr_lib::shared_ptr<urdf::Collision> urdf_traverser::CollisionPtr

Definition at line 66 of file Types.h.

typedef shr_lib::shared_ptr<urdf::Cylinder> urdf_traverser::CylinderPtr

Definition at line 65 of file Types.h.

typedef Eigen::Transform<double, 3, Eigen::Affine> urdf_traverser::EigenTransform

Definition at line 52 of file Types.h.

Definition at line 171 of file RecursionParams.h.

Definition at line 192 of file RecursionParams.h.

typedef shr_lib::shared_ptr<urdf::Geometry> urdf_traverser::GeometryPtr

Definition at line 61 of file Types.h.

typedef shr_lib::shared_ptr<urdf::Inertial> urdf_traverser::InertialPtr

Definition at line 67 of file Types.h.

typedef shr_lib::shared_ptr<const urdf::Joint> urdf_traverser::JointConstPtr

Definition at line 58 of file Types.h.

typedef shr_lib::shared_ptr<urdf::Joint> urdf_traverser::JointPtr

Definition at line 57 of file Types.h.

typedef shr_lib::shared_ptr<const urdf::Link> urdf_traverser::LinkConstPtr

Definition at line 55 of file Types.h.

typedef shr_lib::shared_ptr<urdf::Link> urdf_traverser::LinkPtr

Definition at line 54 of file Types.h.

Definition at line 147 of file RecursionParams.h.

typedef shr_lib::shared_ptr<urdf::Material> urdf_traverser::MaterialPtr

Definition at line 68 of file Types.h.

typedef shr_lib::shared_ptr<urdf::Mesh> urdf_traverser::MeshPtr

Definition at line 62 of file Types.h.

typedef shr_lib::shared_ptr<const urdf::Model> urdf_traverser::ModelConstPtr

Definition at line 71 of file Types.h.

typedef shr_lib::shared_ptr<urdf::Model> urdf_traverser::ModelPtr

Definition at line 70 of file Types.h.

Definition at line 127 of file RecursionParams.h.

Definition at line 103 of file RecursionParams.h.

typedef shr_lib::shared_ptr<urdf::Sphere> urdf_traverser::SpherePtr

Definition at line 63 of file Types.h.

Definition at line 218 of file RecursionParams.h.

typedef shr_lib::shared_ptr<urdf::Visual> urdf_traverser::VisualPtr

Definition at line 60 of file Types.h.


Function Documentation

bool urdf_traverser::applyTransform ( JointPtr &  joint,
const EigenTransform &  trans,
bool  preMult 
)

Applies the transformation on the joint transform

Parameters:
scaleTransformset to true if the urdf's transforms are to be scaled (using scaleFactor) before applying the transform

Definition at line 188 of file Functions.cpp.

void urdf_traverser::applyTransform ( LinkPtr &  link,
const EigenTransform &  trans,
bool  preMult 
)

Applies the transformation on the link's visuals, collisions and intertial.

Parameters:
scaleTransformset to true if the urdf's transforms are to be scaled (using scaleFactor) before applying the transform

Definition at line 196 of file Functions.cpp.

void urdf_traverser::applyTransform ( const EigenTransform &  t,
urdf::Vector3 &  v 
)

Definition at line 111 of file Functions.cpp.

std::vector< urdf_traverser::JointPtr > urdf_traverser::getChain ( const LinkConstPtr &  from_link,
const LinkConstPtr &  to_link 
)

Returns all joints between from_link and to_link which are along the path between the links - this will only work if there is only one path between both links.

Definition at line 239 of file Functions.cpp.

bool urdf_traverser::getDependencyOrderedJoints ( urdf_traverser::UrdfTraverser traverser,
std::vector< JointPtr > &  result,
const JointPtr &  fromJoint,
bool  allowSplits = true,
bool  onlyActive = true 
)

Returns all joints starting from fromJoint (including fromJoint) within the tree. This is obtained by depth-first traversal, so all joints in the result won't depend on any joints further back in the result set.

bool urdf_traverser::getDependencyOrderedJoints ( urdf_traverser::UrdfTraverser traverser,
std::vector< JointPtr > &  result,
const std::string &  fromLink,
bool  allowSplits = true,
bool  onlyActive = true 
)

Returns all joints down from fromLink within the tree. This is obtained by depth-first traversal, so all joints in the result won't depend on any joints further back in the result set.

Definition at line 142 of file DependencyOrderedJoints.cpp.

bool urdf_traverser::getJointNames ( UrdfTraverser traverser,
const std::string &  fromLink,
const bool  skipFixed,
std::vector< std::string > &  result 
)

Returns all joint names in depth-frist search order starting from fromLink (or from root if fromLink is empty). Only joints *after* the given link are returned.

Definition at line 79 of file JointNames.cpp.

Eigen::Vector3d urdf_traverser::getRotationAxis ( const JointConstPtr &  j)

Definition at line 44 of file Functions.cpp.

Definition at line 145 of file Functions.cpp.

Definition at line 128 of file Functions.cpp.

Definition at line 134 of file Functions.cpp.

urdf_traverser::EigenTransform urdf_traverser::getTransform ( const LinkConstPtr &  from_link,
const LinkConstPtr &  to_link 
)

Definition at line 140 of file Functions.cpp.

Eigen::Matrix4d urdf_traverser::getTransformMatrix ( const LinkConstPtr &  from_link,
const LinkConstPtr &  to_link 
)

Definition at line 161 of file Functions.cpp.

bool urdf_traverser::hasFixedJoints ( UrdfTraverser traverser,
const std::string &  fromLink 
)

returns true if there are any fixed joints down from from_link Only joints *after* the given link are returned.

Definition at line 56 of file ActiveJoints.cpp.

bool urdf_traverser::isActive ( const JointPtr &  joint)

<ORGANIZATION> = Jennifer Buehler <COPYRIGHT holder>=""> = Jennifer Buehler

Copyright (c) 2016 Jennifer Buehler All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: * Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the name of the <ORGANIZATION> nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT holder>=""> BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ------------------------------------------------------------------------------

Definition at line 36 of file Functions.cpp.

bool urdf_traverser::isChildJointOf ( const LinkConstPtr &  parent,
const JointConstPtr &  joint 
)

Definition at line 288 of file Functions.cpp.

bool urdf_traverser::isChildOf ( const LinkConstPtr &  parent,
const LinkConstPtr &  child 
)

Definition at line 278 of file Functions.cpp.

bool urdf_traverser::jointTransformForAxis ( const JointConstPtr &  joint,
const Eigen::Vector3d &  axis,
Eigen::Quaterniond &  rotation 
)
Returns:
true if this joint needs a transformation to align its rotation axis with the given axis. In this case the rotation parameter contains the necessary rotation.

Definition at line 309 of file Functions.cpp.

bool urdf_traverser::printModel ( urdf_traverser::UrdfTraverser traverser,
const std::string &  fromLink,
bool  verbose 
)

Definition at line 100 of file PrintModel.cpp.

bool urdf_traverser::printModel ( urdf_traverser::UrdfTraverser traverser,
bool  verbose 
)

Definition at line 109 of file PrintModel.cpp.

void urdf_traverser::scaleTranslation ( EigenTransform &  t,
double  scale_factor 
)

Scales up the **translation part** of the transform t by the given factor

Definition at line 87 of file Functions.cpp.

bool urdf_traverser::scaleTranslation ( JointPtr &  joint,
double  scale_factor 
)

scales the translation part of the joint transform by the given factor

Definition at line 49 of file Functions.cpp.

void urdf_traverser::scaleTranslation ( LinkPtr &  link,
double  scale_factor 
)

scales the translation part of the origins of visuals/collisions/inertial by the given factor

Definition at line 56 of file Functions.cpp.

void urdf_traverser::setTransform ( const EigenTransform &  t,
urdf::Pose &  p 
)

Definition at line 97 of file Functions.cpp.

void urdf_traverser::setTransform ( const EigenTransform &  t,
JointPtr &  joint 
)

Definition at line 122 of file Functions.cpp.



urdf_traverser
Author(s): Jennifer Buehler
autogenerated on Fri Mar 1 2019 03:38:07