Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00037 #include "fcl/articulated_model/joint.h"
00038 #include "fcl/articulated_model/link.h"
00039 #include "fcl/articulated_model/joint_config.h"
00040 
00041 namespace fcl
00042 {
00043 
00044 Joint::Joint(const boost::shared_ptr<Link>& link_parent, const boost::shared_ptr<Link>& link_child,
00045              const Transform3f& transform_to_parent,
00046              const std::string& name) :
00047   link_parent_(link_parent), link_child_(link_child),
00048   transform_to_parent_(transform_to_parent),
00049   name_(name)
00050 {}
00051 
00052 Joint::Joint(const std::string& name) :
00053   name_(name)
00054 {
00055 }
00056 
00057 const std::string& Joint::getName() const
00058 {
00059   return name_;
00060 }
00061 
00062 void Joint::setName(const std::string& name)
00063 {
00064   name_ = name;
00065 }
00066 
00067 boost::shared_ptr<JointConfig> Joint::getJointConfig() const
00068 {
00069   return joint_cfg_;
00070 }
00071 
00072 void Joint::setJointConfig(const boost::shared_ptr<JointConfig>& joint_cfg)
00073 {
00074   joint_cfg_ = joint_cfg;
00075 }
00076 
00077 boost::shared_ptr<Link> Joint::getParentLink() const
00078 {
00079   return link_parent_.lock();
00080 }
00081 
00082 boost::shared_ptr<Link> Joint::getChildLink() const
00083 {
00084   return link_child_.lock();
00085 }
00086 
00087 void Joint::setParentLink(const boost::shared_ptr<Link>& link)
00088 {
00089   link_parent_ = link;
00090 }
00091 
00092 void Joint::setChildLink(const boost::shared_ptr<Link>& link)
00093 {
00094   link_child_ = link;
00095 }
00096 
00097 JointType Joint::getJointType() const
00098 {
00099   return type_;
00100 }
00101 
00102 const Transform3f& Joint::getTransformToParent() const
00103 {
00104   return transform_to_parent_;
00105 }
00106 
00107 void Joint::setTransformToParent(const Transform3f& t)
00108 {
00109   transform_to_parent_ = t;
00110 }
00111 
00112 
00113 PrismaticJoint::PrismaticJoint(const boost::shared_ptr<Link>& link_parent, const boost::shared_ptr<Link>& link_child,
00114                                const Transform3f& transform_to_parent,
00115                                const std::string& name,
00116                                const Vec3f& axis) :
00117   Joint(link_parent, link_child, transform_to_parent, name),
00118   axis_(axis)
00119 {
00120   type_ = JT_PRISMATIC;
00121 }
00122 
00123 const Vec3f& PrismaticJoint::getAxis() const
00124 {
00125   return axis_;
00126 }
00127 
00128 std::size_t PrismaticJoint::getNumDofs() const
00129 {
00130   return 1;
00131 }
00132 
00133 Transform3f PrismaticJoint::getLocalTransform() const
00134 {
00135   const Quaternion3f& quat = transform_to_parent_.getQuatRotation();
00136   const Vec3f& transl = transform_to_parent_.getTranslation();
00137   return Transform3f(quat, quat.transform(axis_ * (*joint_cfg_)[0]) + transl);
00138 }
00139 
00140 
00141 RevoluteJoint::RevoluteJoint(const boost::shared_ptr<Link>& link_parent, const boost::shared_ptr<Link>& link_child,
00142                              const Transform3f& transform_to_parent,
00143                              const std::string& name,
00144                              const Vec3f& axis) :
00145   Joint(link_parent, link_child, transform_to_parent, name),
00146   axis_(axis)
00147 {
00148   type_ = JT_REVOLUTE;
00149 }
00150 
00151 const Vec3f& RevoluteJoint::getAxis() const
00152 {
00153   return axis_;
00154 }
00155 
00156 std::size_t RevoluteJoint::getNumDofs() const
00157 {
00158   return 1;
00159 }
00160 
00161 Transform3f RevoluteJoint::getLocalTransform() const
00162 {
00163   Quaternion3f quat;
00164   quat.fromAxisAngle(axis_, (*joint_cfg_)[0]);
00165   return Transform3f(transform_to_parent_.getQuatRotation() * quat, transform_to_parent_.getTranslation());
00166 }
00167 
00168 
00169 BallEulerJoint::BallEulerJoint(const boost::shared_ptr<Link>& link_parent, const boost::shared_ptr<Link>& link_child,
00170                                const Transform3f& transform_to_parent,
00171                                const std::string& name) :
00172   Joint(link_parent, link_child, transform_to_parent, name)
00173 {}
00174 
00175 std::size_t BallEulerJoint::getNumDofs() const
00176 {
00177   return 3;
00178 }
00179 
00180 Transform3f BallEulerJoint::getLocalTransform() const
00181 {
00182   Matrix3f rot;
00183   rot.setEulerYPR((*joint_cfg_)[0], (*joint_cfg_)[1], (*joint_cfg_)[2]);
00184   return transform_to_parent_ * Transform3f(rot);
00185 }
00186 
00187 
00188 
00189 
00190 
00191 }