spatial-dyn
forward_kinematics.h
1 
10 #ifndef SPATIAL_DYN_ALGORITHMS_FORWARD_KINEMATICS_H_
11 #define SPATIAL_DYN_ALGORITHMS_FORWARD_KINEMATICS_H_
12 
13 #include "spatial_dyn/eigen/spatial_math.h"
14 #include "spatial_dyn/structs/articulated_body.h"
15 
16 namespace spatial_dyn {
17 
39 Eigen::Vector3d Position(const ArticulatedBody& ab, int link = -1,
40  const Eigen::Vector3d& offset = Eigen::Vector3d::Zero());
41 
55 Eigen::Vector3d Position(const ArticulatedBody& ab,
56  Eigen::Ref<const Eigen::VectorXd> q, int link = -1,
57  const Eigen::Vector3d& offset = Eigen::Vector3d::Zero());
58 
69 Eigen::Quaterniond Orientation(const ArticulatedBody& ab, int link = -1);
70 
83 Eigen::Quaterniond Orientation(const ArticulatedBody& ab,
84  Eigen::Ref<const Eigen::VectorXd> q, int link = -1);
85 
97 Eigen::Isometry3d CartesianPose(const ArticulatedBody& ab, int link = -1,
98  const Eigen::Vector3d& offset = Eigen::Vector3d::Zero());
99 
113 Eigen::Isometry3d CartesianPose(const ArticulatedBody& ab,
114  Eigen::Ref<const Eigen::VectorXd> q, int link = -1,
115  const Eigen::Vector3d& offset = Eigen::Vector3d::Zero());
116 
131 const Eigen::Matrix6Xd& Jacobian(const ArticulatedBody& ab, int link = -1,
132  const Eigen::Vector3d& offset = Eigen::Vector3d::Zero());
133 
147 Eigen::Matrix6Xd Jacobian(const ArticulatedBody& ab,
148  Eigen::Ref<const Eigen::VectorXd> q, int link = -1,
149  const Eigen::Vector3d& offset = Eigen::Vector3d::Zero());
150 
165 Eigen::Ref<const Eigen::Matrix3Xd> LinearJacobian(const ArticulatedBody& ab, int link = -1,
166  const Eigen::Vector3d& offset = Eigen::Vector3d::Zero());
167 
181 Eigen::Matrix3Xd LinearJacobian(const ArticulatedBody& ab,
182  Eigen::Ref<const Eigen::VectorXd> q, int link = -1,
183  const Eigen::Vector3d& offset = Eigen::Vector3d::Zero());
184 
200 Eigen::Ref<const Eigen::Matrix3Xd> AngularJacobian(const ArticulatedBody& ab, int link = -1);
201 
214 Eigen::Matrix3Xd AngularJacobian(const ArticulatedBody& ab,
215  Eigen::Ref<const Eigen::VectorXd> q, int link = -1);
216 
226 Eigen::Tensor3d Hessian(const ArticulatedBody& ab, int link = -1,
227  const Eigen::Vector3d& offset = Eigen::Vector3d::Zero());
228  // defgroup cpp_forward_kinematics
232 
233 } // namespace spatial_dyn
234 
235 #endif // SPATIAL_DYN_ALGORITHMS_FORWARD_KINEMATICS_H_
Eigen::Ref< const Eigen::Matrix3Xd > LinearJacobian(const ArticulatedBody &ab, int link, const Eigen::Vector3d &offset)
Definition: forward_kinematics.cc:113
Eigen::Vector3d Position(const ArticulatedBody &ab, int link, const Eigen::Vector3d &offset)
Definition: forward_kinematics.cc:16
Eigen::Quaterniond Orientation(const ArticulatedBody &ab, int link)
Definition: forward_kinematics.cc:32
Eigen::Isometry3d CartesianPose(const ArticulatedBody &ab, int link, const Eigen::Vector3d &offset)
Definition: forward_kinematics.cc:47
const Eigen::Matrix6Xd & Jacobian(const ArticulatedBody &ab, int link, const Eigen::Vector3d &offset)
Definition: forward_kinematics.cc:57
Eigen::Ref< const Eigen::Matrix3Xd > AngularJacobian(const ArticulatedBody &ab, int link)
Definition: forward_kinematics.cc:123
Eigen::Tensor3d Hessian(const ArticulatedBody &ab, int link, const Eigen::Vector3d &offset)
Definition: forward_kinematics.cc:133
Definition: discrete_dynamics.cc:21