Resurgence (PY2022)
Codebase for the Husky Robotics 2021-2022 rover Resurgence
Loading...
Searching...
No Matches
kinematics::InverseArmKinematics< D, N > Class Template Referenceabstract

A class that calculates the inverse kinematics of an arm. More...

#include <InverseArmKinematics.h>

Inheritance diagram for kinematics::InverseArmKinematics< D, N >:
Collaboration diagram for kinematics::InverseArmKinematics< D, N >:

Public Member Functions

 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.
 

Protected Member Functions

virtual navtypes::Vectord< N > solve (const navtypes::Vectord< D > &eePos, const navtypes::Vectord< N > &jointAngles, bool &success) const =0
 Solve for the joint angles that yield the given EE position.
 

Protected Attributes

const std::shared_ptr< const ForwardArmKinematics< D, N > > fk
 

Detailed Description

template<unsigned int D, unsigned int N>
class kinematics::InverseArmKinematics< D, N >

A class that calculates the inverse kinematics of an arm.

Template Parameters
DThe number of dimensions of the end effector space.
NThe number of joints in the arm.

Constructor & Destructor Documentation

◆ InverseArmKinematics()

template<unsigned int D, unsigned int N>
kinematics::InverseArmKinematics< D, N >::InverseArmKinematics ( std::shared_ptr< const ForwardArmKinematics< D, N > > fk)
inline

Construct an IK object.

Parameters
fkThe forward kinematics that are inverted by this class.

Member Function Documentation

◆ eePosToJointPos() [1/2]

template<unsigned int D, unsigned int N>
navtypes::Vectord< N > kinematics::InverseArmKinematics< D, N >::eePosToJointPos ( const navtypes::Vectord< D > & eePos,
const navtypes::Vectord< N > & currJointPos ) const
inline

Calculate the joint angles that yield the desired EE position.

Warning
This may fail, for multiple reasons. To check for success, use the overload of this method with the success parameter.
Parameters
eePosDesired EE position.
currJointPosThe current joint angles.
Returns
navtypes::Vectord<N> Joint angles that yield the desired EE position.

◆ eePosToJointPos() [2/2]

template<unsigned int D, unsigned int N>
virtual navtypes::Vectord< N > kinematics::InverseArmKinematics< D, N >::eePosToJointPos ( const navtypes::Vectord< D > & eePos,
const navtypes::Vectord< N > & jointAngles,
bool & success ) const
inlinevirtual

Solve for the joint angles that yield the given EE position.

Parameters
eePosThe desired end effector position.
currJointPosThe current joint angles. Used as a starting guess for the IK solver.
[out]successOutput 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.

◆ solve()

template<unsigned int D, unsigned int N>
virtual navtypes::Vectord< N > kinematics::InverseArmKinematics< D, N >::solve ( const navtypes::Vectord< D > & eePos,
const navtypes::Vectord< N > & jointAngles,
bool & success ) const
protectedpure virtual

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
eePosThe desired end effector position.
currJointPosThe current joint angles. Used as a starting guess for the IK solver.
[out]successOutput 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.

Implemented in kinematics::ArmKinematics< D, N >, and kinematics::ArmKinematics< 2, N >.


The documentation for this class was generated from the following file: