|
Eigen::Vector3d | spatial_dyn::Position (const ArticulatedBody &ab, int link, const Eigen::Vector3d &offset) |
|
Eigen::Vector3d | spatial_dyn::Position (const ArticulatedBody &ab, Eigen::Ref< const Eigen::VectorXd > q, int link, const Eigen::Vector3d &offset) |
|
Eigen::Quaterniond | spatial_dyn::Orientation (const ArticulatedBody &ab, int link) |
|
Eigen::Quaterniond | spatial_dyn::Orientation (const ArticulatedBody &ab, Eigen::Ref< const Eigen::VectorXd > q, int link) |
|
Eigen::Isometry3d | spatial_dyn::CartesianPose (const ArticulatedBody &ab, int link, const Eigen::Vector3d &offset) |
|
Eigen::Isometry3d | spatial_dyn::CartesianPose (const ArticulatedBody &ab, Eigen::Ref< const Eigen::VectorXd > q, int link, const Eigen::Vector3d &offset) |
|
const Eigen::Matrix6Xd & | spatial_dyn::Jacobian (const ArticulatedBody &ab, int link, const Eigen::Vector3d &offset) |
|
Eigen::Matrix6Xd | spatial_dyn::Jacobian (const ArticulatedBody &ab, Eigen::Ref< const Eigen::VectorXd > q, int link, const Eigen::Vector3d &offset) |
|
Eigen::Ref< const Eigen::Matrix3Xd > | spatial_dyn::LinearJacobian (const ArticulatedBody &ab, int link, const Eigen::Vector3d &offset) |
|
Eigen::Matrix3Xd | spatial_dyn::LinearJacobian (const ArticulatedBody &ab, Eigen::Ref< const Eigen::VectorXd > q, int link, const Eigen::Vector3d &offset) |
|
Eigen::Ref< const Eigen::Matrix3Xd > | spatial_dyn::AngularJacobian (const ArticulatedBody &ab, int link) |
|
Eigen::Matrix3Xd | spatial_dyn::AngularJacobian (const ArticulatedBody &ab, Eigen::Ref< const Eigen::VectorXd > q, int link) |
|
Eigen::Tensor3d | spatial_dyn::Hessian (const ArticulatedBody &ab, int link, const Eigen::Vector3d &offset) |
|
C++ implementation of spatial_dyn forward kinematics algorithms.
- See also
- Python: py_forward_kinematics
◆ AngularJacobian() [1/2]
Eigen::Matrix3Xd spatial_dyn::AngularJacobian |
( |
const ArticulatedBody & |
ab, |
|
|
Eigen::Ref< const Eigen::VectorXd > |
q, |
|
|
int |
link = -1 |
|
) |
| |
Compute the world frame angular Jacobian of the given operational point.
Runs in O(n) time.
- Parameters
-
ab | Articulated body. |
q | Joint configuration. |
link | Index of the desired link. |
- Returns
- Angular Jacobian (bottom 3 rows of the basic Jacobian) represented in the world frame.
- See also
- Python: spatialdyn.angular_jacobian()
◆ AngularJacobian() [2/2]
Eigen::Ref< const Eigen::Matrix3Xd > spatial_dyn::AngularJacobian |
( |
const ArticulatedBody & |
ab, |
|
|
int |
link = -1 |
|
) |
| |
Compute the world frame angular Jacobian of the given operational point.
The computation is cached such that the first call to Jacobian() runs in O(n) time, and subsequent calls with the same joint position, link, and offset run in O(1) time. AngularJacobian() uses the last offset passed to Jacobian() or LinearJacobian() for caching, and therefore should be called after Jacobian() or LinearJacobian() to avoid unnecessary computations with a nonzero offset.
- Parameters
-
ab | Articulated body. |
link | Index of the desired link. |
- Returns
- Reference to the bottom 3 rows of the cached basic Jacobian represented in the world frame.
- See also
- Python: spatialdyn.angular_jacobian()
◆ CartesianPose() [1/2]
Eigen::Isometry3d spatial_dyn::CartesianPose |
( |
const ArticulatedBody & |
ab, |
|
|
Eigen::Ref< const Eigen::VectorXd > |
q, |
|
|
int |
link = -1 , |
|
|
const Eigen::Vector3d & |
offset = Eigen::Vector3d::Zero() |
|
) |
| |
Compute the world frame pose of an offset vector in link i
given articulated body configuration q.
Runs in O(n) time.
- Parameters
-
ab | Articulated body. |
q | Joint configuration. |
link | Index of the desired link. |
offset | Vector offset in link i . |
- Returns
- World frame pose of the offset in link
i
.
- See also
- Python: spatialdyn.cartesian_pose()
◆ CartesianPose() [2/2]
Eigen::Isometry3d spatial_dyn::CartesianPose |
( |
const ArticulatedBody & |
ab, |
|
|
int |
link = -1 , |
|
|
const Eigen::Vector3d & |
offset = Eigen::Vector3d::Zero() |
|
) |
| |
Compute the world frame pose of an offset vector in link i
.
Uses the articulated body's cached world transforms to run in O(1) time.
- Parameters
-
ab | Articulated body. |
link | Index of the desired link. |
offset | Vector offset in link i . |
- Returns
- World frame pose of the offset in link
i
.
- See also
- Python: spatialdyn.cartesian_pose()
◆ Hessian()
Eigen::Tensor3d spatial_dyn::Hessian |
( |
const ArticulatedBody & |
ab, |
|
|
int |
link = -1 , |
|
|
const Eigen::Vector3d & |
offset = Eigen::Vector3d::Zero() |
|
) |
| |
Compute the world frame Hessian of the given operational point.
- Parameters
-
ab | Articulated body. |
link | Index of the desired link. |
offset | Vector offset of the operational point in link i . |
- Returns
- [n x n x 6] Hessian represented in the world frame.
- See also
- Python: spatialdyn.hessian()
◆ Jacobian() [1/2]
Eigen::Matrix6Xd spatial_dyn::Jacobian |
( |
const ArticulatedBody & |
ab, |
|
|
Eigen::Ref< const Eigen::VectorXd > |
q, |
|
|
int |
link = -1 , |
|
|
const Eigen::Vector3d & |
offset = Eigen::Vector3d::Zero() |
|
) |
| |
Compute the world frame basic Jacobian of the given operational point.
Runs in O(n) time.
- Parameters
-
ab | Articulated body. |
q | Joint configuration. |
link | Index of the desired link. |
offset | Vector offset of the operational point in link i . |
- Returns
- Basic Jacobian (linear stacked above angular) represented in the world frame.
- See also
- Python: spatialdyn.jacobian()
◆ Jacobian() [2/2]
const Eigen::Matrix6Xd & spatial_dyn::Jacobian |
( |
const ArticulatedBody & |
ab, |
|
|
int |
link = -1 , |
|
|
const Eigen::Vector3d & |
offset = Eigen::Vector3d::Zero() |
|
) |
| |
Compute the world frame basic Jacobian of the given operational point.
The computation is cached such that the first call to Jacobian() runs in O(n) time, and subsequent calls with the same joint position, link, and offset run in O(1) time.
- Parameters
-
ab | Articulated body. |
link | Index of the desired link. |
offset | Vector offset of the operational point in link i . |
- Returns
- Reference to the cached basic Jacobian (linear stacked above angular) represented in the world frame.
- See also
- Python: spatialdyn.jacobian()
◆ LinearJacobian() [1/2]
Eigen::Matrix3Xd spatial_dyn::LinearJacobian |
( |
const ArticulatedBody & |
ab, |
|
|
Eigen::Ref< const Eigen::VectorXd > |
q, |
|
|
int |
link = -1 , |
|
|
const Eigen::Vector3d & |
offset = Eigen::Vector3d::Zero() |
|
) |
| |
Compute the world frame linear Jacobian of the given operational point.
A Runs in O(n) time.
- Parameters
-
ab | Articulated body. |
q | Joint configuration. |
link | Index of the desired link. |
offset | Vector offset of the operational point in link i . |
- Returns
- Linear Jacobian (top 3 rows of the basic Jacobian) represented in the world frame.
- See also
- Python: spatialdyn.linear_jacobian()
◆ LinearJacobian() [2/2]
Eigen::Ref< const Eigen::Matrix3Xd > spatial_dyn::LinearJacobian |
( |
const ArticulatedBody & |
ab, |
|
|
int |
link = -1 , |
|
|
const Eigen::Vector3d & |
offset = Eigen::Vector3d::Zero() |
|
) |
| |
Compute the world frame linear Jacobian of the given operational point.
The computation is cached such that the first call to Jacobian() runs in O(n) time, and subsequent calls with the same joint position, link, and offset run in O(1) time.
- Parameters
-
ab | Articulated body. |
link | Index of the desired link. |
offset | Vector offset of the operational point in link i . |
- Returns
- Reference to the top 3 rows of the cached basic Jacobian represented in the world frame.
- See also
- Python: spatialdyn.linear_jacobian()
◆ Orientation() [1/2]
Eigen::Quaterniond spatial_dyn::Orientation |
( |
const ArticulatedBody & |
ab, |
|
|
Eigen::Ref< const Eigen::VectorXd > |
q, |
|
|
int |
link = -1 |
|
) |
| |
Compute the world frame orientation of link i
given articulated body configuration q.
Runs in O(n) time.
- Parameters
-
ab | Articulated body. |
q | Joint configuration. |
link | Index of the desired link. |
- Returns
- World frame orientation of link
i
.
- See also
- Python: spatialdyn.orientation()
◆ Orientation() [2/2]
Eigen::Quaterniond spatial_dyn::Orientation |
( |
const ArticulatedBody & |
ab, |
|
|
int |
link = -1 |
|
) |
| |
Compute the world frame orientation of link i
.
Uses the articulated body's cached world transforms to run in O(1) time.
- Parameters
-
ab | Articulated body. |
link | Index of the desired link. |
- Returns
- World frame orientation of link
i
.
- See also
- Python: spatialdyn.orientation()
◆ Position() [1/2]
Eigen::Vector3d spatial_dyn::Position |
( |
const ArticulatedBody & |
ab, |
|
|
Eigen::Ref< const Eigen::VectorXd > |
q, |
|
|
int |
link = -1 , |
|
|
const Eigen::Vector3d & |
offset = Eigen::Vector3d::Zero() |
|
) |
| |
Compute the world frame position of an offset vector in link i
given articulated body configuration q.
Runs in O(n) time.
- Parameters
-
ab | Articulated body. |
q | Joint configuration. |
link | Index of the desired link. |
offset | Vector offset in link i . |
- Returns
- World frame position of the offset in link
i
.
- See also
- Python: spatialdyn.position()
◆ Position() [2/2]
Eigen::Vector3d spatial_dyn::Position |
( |
const ArticulatedBody & |
ab, |
|
|
int |
link = -1 , |
|
|
const Eigen::Vector3d & |
offset = Eigen::Vector3d::Zero() |
|
) |
| |
Compute the world frame position of an offset vector in link i
.
Uses the articulated body's cached world transforms to run in O(1) time.
- Parameters
-
ab | Articulated body. |
link | Index of the desired link. |
offset | Vector offset in link i . |
- Returns
- World frame position of the offset in link
i
.
- See also
- Python: spatialdyn.position()