Go to the documentation of this file.00001 
00019 #ifndef URDF2GRASPIT_CONVERSIONRESULT_H
00020 #define URDF2GRASPIT_CONVERSIONRESULT_H
00021 
00022 
00023 #include <string>
00024 #include <map>
00025 #include <urdf2inventor/ConversionResult.h>
00026 #include <urdf2inventor/MeshConvertRecursionParams.h>
00027 
00028 namespace urdf2graspit
00029 {
00030 
00031 class ConversionParameters:
00032     public urdf2inventor::ConversionParameters
00033 {
00034 public:
00035     explicit ConversionParameters(const std::string& _robotName,
00036         const std::string& _rootLinkName,
00037         const std::string& material,
00038         const std::vector<std::string>& _fingerRoots,
00039         const EigenTransform& addVisualTransform):
00040         urdf2inventor::ConversionParameters(_rootLinkName, material, addVisualTransform),
00041         robotName(_robotName),
00042         fingerRoots(_fingerRoots){}
00043     ConversionParameters(const ConversionParameters& o):
00044         urdf2inventor::ConversionParameters(o),
00045         robotName(o.robotName),
00046         fingerRoots(o.fingerRoots) {}
00047 
00048     virtual ~ConversionParameters() {}
00049     std::string robotName;
00050     std::vector<std::string> fingerRoots;
00051 };
00052 
00053 
00057 
00058 
00059 
00060 
00061 
00062 
00063 
00064 
00065 
00066 
00067 
00068 
00069 
00070 
00071 
00072 
00073 
00074 
00075 
00076 
00077 
00078 
00079 
00085 class ConversionResult:
00086     public urdf2inventor::ConversionResult<std::string>
00087 {
00088 public:
00089     typedef std::string MeshFormatT;
00090 
00091     explicit ConversionResult(const std::string& _meshOutputExtension,
00092             const std::string& _meshOutputDirectoryName,
00093             const std::string& _texOutputDirectoryName):
00094         urdf2inventor::ConversionResult<MeshFormatT>(_meshOutputExtension, _meshOutputDirectoryName, _texOutputDirectoryName){}
00095     ConversionResult(const ConversionResult& o):
00096         urdf2inventor::ConversionResult<MeshFormatT>(o),
00097         robotXML(o.robotXML),
00098         meshXMLDesc(o.meshXMLDesc),
00099         eigenGraspXML(o.eigenGraspXML),
00100         
00101         world(o.world){}
00102 
00103     virtual ~ConversionResult() {}
00104 
00105     std::string robotXML;
00106 
00107     
00108     std::map<std::string, std::string> meshXMLDesc;
00109 
00110     
00111     std::string eigenGraspXML;
00112 
00113     
00114     
00115 
00116     
00117     std::string world;
00118 };
00119 
00120 }  
00121 #endif   // URDF2GRASPIT_CONVERSIONRESULT_H