Public Types | Public Member Functions | Static Public Attributes | Protected Member Functions | Private Member Functions | Private Attributes
urdf2inventor::Urdf2Inventor Class Reference

This class provides functions to transform a robot described in URDF to the inventor format. More...

#include <Urdf2Inventor.h>

List of all members.

Public Types

typedef
baselib_binding::shared_ptr
< ConversionParameters >::type 
ConversionParametersPtr
typedef
baselib_binding::shared_ptr
< ConversionResultT >::type 
ConversionResultPtr
typedef ConversionResult
< MeshFormat
ConversionResultT
typedef
urdf_traverser::EigenTransform 
EigenTransform
typedef
urdf_traverser::JointConstPtr 
JointConstPtr
typedef urdf_traverser::JointPtr JointPtr
typedef
urdf_traverser::LinkConstPtr 
LinkConstPtr
typedef urdf_traverser::LinkPtr LinkPtr
typedef
baselib_binding::shared_ptr
< MeshConvertRecursionParamsT >
::type 
MeshConvertRecursionParamsPtr
typedef
MeshConvertRecursionParams
< MeshFormat
MeshConvertRecursionParamsT
typedef std::string MeshFormat
typedef
baselib_binding::shared_ptr
< const
urdf_traverser::UrdfTraverser >
::type 
UrdfTraverserConstPtr
typedef
baselib_binding::shared_ptr
< urdf_traverser::UrdfTraverser >
::type 
UrdfTraverserPtr

Public Member Functions

bool allRotationsToAxis (const std::string &fromLinkName, const Eigen::Vector3d &axis)
void cleanup ()
virtual ConversionResultPtr convert (const ConversionParametersPtr &params, const MeshConvertRecursionParamsPtr &meshParams=MeshConvertRecursionParamsPtr())
SoNode * getAsInventor (const std::string &fromLink, bool useScaleFactor, bool addAxes, float axesRadius, float axesLength, const EigenTransform &addVisualTransform, std::set< std::string > *textureFiles)
ConversionParametersPtr getBasicConversionParams (const std::string &rootLink, const std::string &material, const EigenTransform &addVisualTransform)
bool getJointNames (const std::string &fromLink, const bool skipFixed, std::vector< std::string > &result)
bool joinFixedLinks (const std::string &from_link)
ConversionResultPtr loadAndConvert (const std::string &urdfFilename, bool joinFixed, const ConversionParametersPtr &params)
bool loadModelFromFile (const std::string &urdfFilename)
void printJointNames (const std::string &fromLink)
bool printModel ()
bool printModel (const std::string &fromLink)
 Urdf2Inventor (const UrdfTraverserPtr &traverser, float _scaleFactor=1)
bool writeAsInventor (const std::string &outputFilename, const std::string &fromLink, bool useScaleFactor, const EigenTransform &addVisualTransform, bool _addAxes=false, float _axesRadius=0.003, float _axesLength=0.015)
 ~Urdf2Inventor ()

Static Public Attributes

static std::string MESH_OUTPUT_DIRECTORY_NAME = "iv/"
static std::string OUTPUT_EXTENSION = ".iv"
static std::string TEX_OUTPUT_DIRECTORY_NAME = "textures/"

Protected Member Functions

void addLocalAxes (const LinkConstPtr &link, SoSeparator *addToNode, bool useScaleFactor, float _axesRadius, float _axesLength) const
float getScaleFactor () const
EigenTransform getTransform (const LinkPtr &from_link, const JointPtr &to_joint)
UrdfTraverserPtr getTraverser ()
virtual ConversionResultPtr postConvert (const ConversionParametersPtr &params, ConversionResultPtr &result)
virtual ConversionResultPtr preConvert (const ConversionParametersPtr &params)
UrdfTraverserConstPtr readTraverser () const
bool scale ()

Private Member Functions

SoNode * getAsInventor (const LinkPtr &from_link, bool useScaleFactor, bool _addAxes, float _axesRadius, float _axesLength, const EigenTransform &addTransform, std::set< std::string > *textureFiles)
bool writeAsInventor (const std::string &outFilename, const LinkPtr &from_link, bool useScaleFactor, const EigenTransform &addTransform, bool _addAxes=false, float _axesRadius=0.003, float _axesLength=0.015)
bool writeInventorFile (SoNode *node, const std::string &filename)

Private Attributes

bool isScaled
float scaleFactor
UrdfTraverserPtr urdf_traverser

Detailed Description

This class provides functions to transform a robot described in URDF to the inventor format.

Author:
Jennifer Buehler
Date:
March 2016

Definition at line 63 of file Urdf2Inventor.h.


Member Typedef Documentation

Definition at line 70 of file Urdf2Inventor.h.

typedef baselib_binding::shared_ptr<ConversionResultT>::type urdf2inventor::Urdf2Inventor::ConversionResultPtr

Definition at line 69 of file Urdf2Inventor.h.

Definition at line 68 of file Urdf2Inventor.h.

Definition at line 78 of file Urdf2Inventor.h.

Definition at line 82 of file Urdf2Inventor.h.

Definition at line 81 of file Urdf2Inventor.h.

Definition at line 80 of file Urdf2Inventor.h.

Definition at line 79 of file Urdf2Inventor.h.

Definition at line 73 of file Urdf2Inventor.h.

Definition at line 72 of file Urdf2Inventor.h.

Definition at line 67 of file Urdf2Inventor.h.

Definition at line 76 of file Urdf2Inventor.h.

Definition at line 75 of file Urdf2Inventor.h.


Constructor & Destructor Documentation

urdf2inventor::Urdf2Inventor::Urdf2Inventor ( const UrdfTraverserPtr traverser,
float  _scaleFactor = 1 
) [inline, explicit]
Parameters:
traverserthe URDF traverser. Does not need to have a loaded URDF, as method loadAndConvert() will load the URDF into it.
_scaleFactorthe graspit model might have to be scaled (the urdf model is in meters, graspit! in millimeters). This can be specified with this scale factor.

Definition at line 102 of file Urdf2Inventor.h.

Definition at line 111 of file Urdf2Inventor.h.


Member Function Documentation

void Urdf2Inventor::addLocalAxes ( const LinkConstPtr link,
SoSeparator *  addToNode,
bool  useScaleFactor,
float  _axesRadius,
float  _axesLength 
) const [protected]

Definition at line 328 of file Urdf2Inventor.cpp.

bool Urdf2Inventor::allRotationsToAxis ( const std::string &  fromLinkName,
const Eigen::Vector3d &  axis 
)

Transform the URDF such that all rotation axises (in the joint's local reference frame) are this axis

Definition at line 97 of file Urdf2Inventor.cpp.

Cleans up all temporary files written to disk.

Definition at line 257 of file Urdf2Inventor.cpp.

Method which does the conversion from URDF to Inventor. This fist calls the implementation-specific preConvert(), then scales the model (using the scale factor specified in the constructor, unless the model was already scaled before), then converts the individual links mesh files and finally calls implementation-specific postConvert(). To save an inventor file of the *whole* robot, use writeAsInventor() instead.

Parameters:
paramsparameters of the conversion
meshParamsoptional: pre-instantiated MeshConvertRecursionParams. Can be left null and then default is constructed.

Definition at line 173 of file Urdf2Inventor.cpp.

SoNode * Urdf2Inventor::getAsInventor ( const std::string &  fromLink,
bool  useScaleFactor,
bool  addAxes,
float  axesRadius,
float  axesLength,
const EigenTransform addVisualTransform,
std::set< std::string > *  textureFiles 
)

Returns an inventor node for all links down from (and including) from_link. IMPORTANT: This will also load the model, so any other URDF model previously loaded will be overwritten.

Parameters:
useScaleFactorif set to true, the model is scaled up using scale factor set in constructor.
fromLinkif empty string, the root link in the URDF is going to be used. Otherwise, a link name can be set here which will return the model starting from this link name. Returns an inventor node for all links down from (and including) from_link. The model needs to be loaded first by any of the load functions.
useScaleFactorif set to true, the model is scaled up using scale factor set in constructor.
fromLinkif empty string, the root link in the URDF is going to be used. Otherwise, a link name can be set here which will return the model starting from this link name.
addAxesadd the local coordinate system axes of the links to the inventor nodes. z axis is displayed blue, y axis green, x axis red, and the rotation axis pink. Fixed joints axes will be artificially altered to be slightly longer and thinner, so a distinction is visible.
axesRadiusradius of the axes, if _addAxes is true
axesLengthlength of the axes, if _addAxes is true
addVisualTransformthis transform will be post-multiplied on all links' **visuals** (not links!) local transform (their "origin"). This can be used to correct transformation errors which may have been introduced in converting meshes from one format to the other, losing orientation information (for example, .dae has an "up vector" definition which may have been ignored)
textureFilesif not NULL, a list of all texture files (absolute paths) in use are returned here.

Definition at line 444 of file Urdf2Inventor.cpp.

SoNode * Urdf2Inventor::getAsInventor ( const LinkPtr from_link,
bool  useScaleFactor,
bool  _addAxes,
float  _axesRadius,
float  _axesLength,
const EigenTransform addTransform,
std::set< std::string > *  textureFiles 
) [private]

Recursive function which returns an inventor node for all links down from (and including) from_link. See other getAsInventor() function.

Definition at line 366 of file Urdf2Inventor.cpp.

ConversionParametersPtr urdf2inventor::Urdf2Inventor::getBasicConversionParams ( const std::string &  rootLink,
const std::string &  material,
const EigenTransform addVisualTransform 
) [inline]

Constructs a new ConversionParameters object with basic parameters.

Parameters:
rootLinkif empty string, the root link in the URDF is going to be used. Otherwise, a link name can be set here which will convert the model starting from this link name.

Definition at line 203 of file Urdf2Inventor.h.

bool Urdf2Inventor::getJointNames ( 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)

Definition at line 250 of file Urdf2Inventor.cpp.

float urdf2inventor::Urdf2Inventor::getScaleFactor ( ) const [inline, protected]

Definition at line 292 of file Urdf2Inventor.h.

urdf_traverser::EigenTransform Urdf2Inventor::getTransform ( const LinkPtr from_link,
const JointPtr to_joint 
) [protected]

Definition at line 147 of file Urdf2Inventor.cpp.

Definition at line 255 of file Urdf2Inventor.h.

bool Urdf2Inventor::joinFixedLinks ( const std::string &  from_link)

Removes all fixed links in the model by adding visuals and collision geometry to the first parent link which is attached to a non-fixed link. Model has to be loaded with any of the load() methods first.

Definition at line 71 of file Urdf2Inventor.cpp.

Urdf2Inventor::ConversionResultPtr Urdf2Inventor::loadAndConvert ( const std::string &  urdfFilename,
bool  joinFixed,
const ConversionParametersPtr params 
)

Loads the URDF file into the UrdfTraverser (instance passed into the constructor), then joins fixed links (only if joinFixed) and then converts the URDF file to inventor mesh files by calling convert().

Definition at line 569 of file Urdf2Inventor.cpp.

bool Urdf2Inventor::loadModelFromFile ( const std::string &  urdfFilename)

Loads the URDF model from file into the UrdfTraverser (instance passed into the constructor),

Definition at line 141 of file Urdf2Inventor.cpp.

Method called by convert() which can be implemented by subclasses to do any operations required *after* the main body of convert() has been done. See also preConvert().

Parameters:
rootLinkthe conversion is to be done starting from this link.
resultthe conversion result so far. This is the object which has been returned by preConvert(), with changes applied by the main body of convert() applied to the base class fields.
Returns:
Has to be the same as result, with possible changes applied. Set ConversionResult::success to false to indicate failure, or to true to indicate success.

Definition at line 166 of file Urdf2Inventor.cpp.

Method called by convert() which can be implemented by subclasses to return a different type of ConversionResult and do any operations required *before* the main body of convert() is being done. See also postConvert().

Parameters:
rootLinkthe conversion is to be done starting from this link.
Returns:
NULL/invalid shared ptr if pre-conversion failed.

Definition at line 159 of file Urdf2Inventor.cpp.

void Urdf2Inventor::printJointNames ( const std::string &  fromLink)

Prints the joint names. Can't be const in this version because of the use of a recursive method.

Definition at line 292 of file Urdf2Inventor.cpp.

Prints the structure of the URDF to standard out

Definition at line 244 of file Urdf2Inventor.cpp.

bool Urdf2Inventor::printModel ( const std::string &  fromLink)

prints the URDF model to standard out, starting from this link.

Definition at line 239 of file Urdf2Inventor.cpp.

Definition at line 260 of file Urdf2Inventor.h.

bool Urdf2Inventor::scale ( ) [protected]

scale the model and the meshes

Definition at line 121 of file Urdf2Inventor.cpp.

bool Urdf2Inventor::writeAsInventor ( const std::string &  outputFilename,
const std::string &  fromLink,
bool  useScaleFactor,
const EigenTransform addVisualTransform,
bool  _addAxes = false,
float  _axesRadius = 0.003,
float  _axesLength = 0.015 
)

writes all elements down from fromLink to files in inventor format.

Parameters:
outputFilenamehas to be an inventor filename
fromLinkif empty string, the root link in the URDF is going to be used as starting point. Otherwise, a link name can be set here which will write the model starting from this link name.
addVisualTransformthis transform will be post-multiplied on all links' **visuals** (not links!) local transform (their "origin"). This can be used to correct transformation errors which may have been introduced in converting meshes from one format to the other, losing orientation information (for example, .dae has an "up vector" definition which may have been ignored)
_addAxesdefault value: add the local coordinate system axes of the links to the inventor nodes. z axis is displayed blue, y axis green, x axis red, and the rotation axis pink. Fixed joints axes will be artificially altered to be slightly longer and thinner, so a distinction is visible.
_axesRadiusdefault value: radius of the axes, if _addAxes is true
_axesLengthdefault value: length of the axes, if _addAxes is true

Definition at line 468 of file Urdf2Inventor.cpp.

bool Urdf2Inventor::writeAsInventor ( const std::string &  outFilename,
const LinkPtr from_link,
bool  useScaleFactor,
const EigenTransform addTransform,
bool  _addAxes = false,
float  _axesRadius = 0.003,
float  _axesLength = 0.015 
) [private]

Writes all elements down from from_link to a file in inventor format.

Parameters:
outFilenamehas to be an inventor filename

Definition at line 490 of file Urdf2Inventor.cpp.

bool Urdf2Inventor::writeInventorFile ( SoNode *  node,
const std::string &  filename 
) [private]

Writes the contents of SoNode into the file of given name.

Definition at line 265 of file Urdf2Inventor.cpp.


Member Data Documentation

Definition at line 331 of file Urdf2Inventor.h.

std::string Urdf2Inventor::MESH_OUTPUT_DIRECTORY_NAME = "iv/" [static]

Definition at line 90 of file Urdf2Inventor.h.

std::string Urdf2Inventor::OUTPUT_EXTENSION = ".iv" [static]

Definition at line 86 of file Urdf2Inventor.h.

Definition at line 330 of file Urdf2Inventor.h.

std::string Urdf2Inventor::TEX_OUTPUT_DIRECTORY_NAME = "textures/" [static]

Definition at line 93 of file Urdf2Inventor.h.

Definition at line 327 of file Urdf2Inventor.h.


The documentation for this class was generated from the following files:


urdf2inventor
Author(s): Jennifer Buehler
autogenerated on Fri Mar 1 2019 03:38:11