|
| ArmKinematics (std::shared_ptr< const ForwardArmKinematics< D, N > > forwardKin, std::shared_ptr< const InverseArmKinematics< D, N > > inverseKin) |
|
bool | satisfiesConstraints (const navtypes::Vectord< N > &jointPos) const override |
| Check if the given joint configuration is valid.
|
|
navtypes::Vectord< N > | getSegLens () const override |
| Get the segment lengths for this arm.
|
|
navtypes::Vectord< D > | jointPosToEEPos (const navtypes::Vectord< N > &jointPos) const override |
| Given a joint position, calculate the current EE position.
|
|
navtypes::Matrixd< D, N > | getJacobian (const navtypes::Vectord< N > &jointPos) const override |
| Get the jacobian matrix for the arm at the given joint angles.
|
|
constexpr unsigned int | getNumSegments () const |
| Get the number of segments in this arm.
|
|
constexpr unsigned int | getNumDimensions () const |
| Get the number of dimensions of the end effector space.
|
|
navtypes::Vectord< D > | jointVelToEEVel (const navtypes::Vectord< N > &jointPos, const navtypes::Vectord< N > &jointVel) const |
| Calculate the EE velocity.
|
|
navtypes::Vectord< N > | eeVelToJointVel (const navtypes::Vectord< N > &jointPos, const Eigen::Vector2d &eeVel) const |
| Calculates the joint velocity that yields the desired EE velocity.
|
|
| InverseArmKinematics (std::shared_ptr< const ForwardArmKinematics< D, N > > fk) |
| Construct an IK object.
|
|
navtypes::Vectord< N > | eePosToJointPos (const navtypes::Vectord< D > &eePos, const navtypes::Vectord< N > &currJointPos) const |
| Calculate the joint angles that yield the desired EE position.
|
|
virtual navtypes::Vectord< N > | eePosToJointPos (const navtypes::Vectord< D > &eePos, const navtypes::Vectord< N > &jointAngles, bool &success) const |
| Solve for the joint angles that yield the given EE position.
|
|
template<unsigned int D, unsigned int N>
class kinematics::ArmKinematics< D, N >
A class that combines the forward and inverse kinematics of an arm.
- Template Parameters
-
D | The number of dimensions of the end effector space. |
N | The number of joints in the arm. |
template<unsigned int D, unsigned int N>
|
inlineoverrideprotectedvirtual |
Solve for the joint angles that yield the given EE position.
This method does not need to verify that the solution verifies the FK constraints, or if the target position is within the arm's reach.
- Parameters
-
| eePos | The desired end effector position. |
| currJointPos | The current joint angles. Used as a starting guess for the IK solver. |
[out] | success | Output parameter that signals if the IK solver succeeded. Failure may occur if the target is unreachable or the IK solver exceeds the iteration limit. |
- Returns
- navtypes::Vectord<N> The target joint angles that achieve the desired EE position.
Implements kinematics::InverseArmKinematics< D, N >.