Functions.h
Go to the documentation of this file.
00001 
00031 #ifndef URDF_TRAVERSER_FUNCTIONS_H
00032 #define URDF_TRAVERSER_FUNCTIONS_H
00033 // Copyright Jennifer Buehler
00034 
00041 #include <iostream>
00042 #include <string>
00043 
00044 #include <Eigen/Core>
00045 #include <Eigen/Geometry>
00046 #include <urdf_traverser/Types.h>
00047 
00048 namespace urdf_traverser
00049 {
00050 // Returns the joint's rotation axis as Eigen Vector
00051 extern Eigen::Vector3d getRotationAxis(const JointConstPtr& j);
00052 
00053 // Returns if this is an active joint in the URDF description
00054 extern bool isActive(const JointPtr& joint);
00055 
00056 extern bool isChildOf(const LinkConstPtr& parent, const LinkConstPtr& child);
00057 extern bool isChildJointOf(const LinkConstPtr& parent, const JointConstPtr& joint);
00058 
00063 bool jointTransformForAxis(const JointConstPtr& joint, const Eigen::Vector3d& axis, Eigen::Quaterniond& rotation);
00064 
00068 extern void scaleTranslation(EigenTransform& t, double scale_factor);
00069 
00073 extern bool scaleTranslation(JointPtr& joint, double scale_factor);
00074 
00078 extern void scaleTranslation(LinkPtr& link, double scale_factor);
00079 
00080 
00081 extern void setTransform(const EigenTransform& t, urdf::Pose& p);
00082 extern void setTransform(const EigenTransform& t, JointPtr& joint);
00083 
00084 // Get joint transform to parent
00085 extern EigenTransform getTransform(const urdf::Pose& p);
00086 
00087 // Get joint transform to parent
00088 extern EigenTransform getTransform(const JointConstPtr& joint);
00089 
00090 // Get transform to parent link (transform of link's parent joint)
00091 extern EigenTransform getTransform(const LinkConstPtr& link);
00092 
00093 extern Eigen::Matrix4d getTransformMatrix(const LinkConstPtr& from_link,  const LinkConstPtr& to_link);
00094 
00095 extern EigenTransform getTransform(const LinkConstPtr& from_link,  const LinkConstPtr& to_link);
00096 
00097 
00102 extern bool applyTransform(JointPtr& joint, const EigenTransform& trans, bool preMult);
00103 
00108 extern void applyTransform(LinkPtr& link, const EigenTransform& trans, bool preMult);
00109 
00110 extern void applyTransform(const EigenTransform& t, urdf::Vector3& v);
00111 
00116 extern std::vector<JointPtr> getChain(const LinkConstPtr& from_link, const LinkConstPtr& to_link);
00117 
00118 
00119 
00120 }  // namespace
00121 
00122 #endif  // URDF_TRAVERSER_FUNCTIONS_H


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