Go to the documentation of this file.00001
00019 #ifndef URDF2GRASPIT_XMLFUNCS_H
00020 #define URDF2GRASPIT_XMLFUNCS_H
00021
00022
00023 #include <string>
00024 #include <vector>
00025 #include <urdf2graspit/Types.h>
00026 #include <urdf2graspit/DHParam.h>
00027 #include <ros/ros.h>
00028
00029
00036
00037 namespace urdf2graspit
00038 {
00039 namespace xmlfuncs
00040 {
00041
00047 class FingerChain
00048 {
00049
00050 public:
00051 FingerChain(std::vector<DHParam>& p, std::vector<std::string>& lf, std::vector<std::string>& lt):
00052 prms(p), linkFileNames(lf), linkTypes(lt) {}
00053 FingerChain(const FingerChain& o): prms(o.prms), linkFileNames(o.linkFileNames), linkTypes(o.linkTypes) {}
00054 FingerChain& operator=(const FingerChain& o);
00055
00056
00057 std::vector<DHParam> prms;
00058
00059 std::vector<std::string> linkFileNames;
00060
00061
00062 std::vector<std::string> linkTypes;
00063
00064 friend std::ostream& operator<<(std::ostream& o, const FingerChain& p);
00065 };
00066
00067 extern std::string getLinkDescXML(const LinkPtr& link,
00068 const std::string& mesh_output_extension,
00069 const std::string& material = "plastic");
00070
00076 extern std::string getFingerChain(const FingerChain& c, const Eigen::Vector3d& palmTranslation,
00077 const Eigen::Quaterniond& palmRotation, bool negateJointValues);
00078
00079 extern std::string getDOF(float defaultVel, float maxEffort,
00080 float kp = 1e+9, float kd = 1e+7,
00081 float draggerScale = 20, const std::string& type = "r");
00082
00083
00084 extern std::string getEigenGraspXML(const std::vector<DHParam>& dhparams, bool negateJointValues);
00085
00086 extern std::string getWorldFileTemplate(const std::string& robotName, const std::vector<DHParam>& dhparams,
00087 const std::string& worldFilePathRelToGraspitRoot, bool negateJointValues);
00088
00089 }
00090 }
00091 #endif // URDF2GRASPIT_XMLFUNCS_H