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

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

#include <ForwardArmKinematics.h>

Inheritance diagram for kinematics::ForwardArmKinematics< D, N >:

Public Member Functions

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.
 
virtual navtypes::Vectord< N > getSegLens () const =0
 Get the segment lengths for this arm.
 
virtual bool satisfiesConstraints (const navtypes::Vectord< N > &jointPos) const =0
 Check if the given joint configuration is valid.
 
virtual navtypes::Matrixd< D, N > getJacobian (const navtypes::Vectord< N > &jointPos) const =0
 Get the jacobian matrix for the arm at the given joint angles.
 
virtual navtypes::Vectord< D > jointPosToEEPos (const navtypes::Vectord< N > &jointPos) const =0
 Given a joint position, calculate the current EE position.
 
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.
 

Detailed Description

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

A class that calculates the forward kinematics of an arm.

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

Member Function Documentation

◆ eeVelToJointVel()

template<unsigned int D, unsigned int N>
navtypes::Vectord< N > kinematics::ForwardArmKinematics< D, N >::eeVelToJointVel ( const navtypes::Vectord< N > & jointPos,
const Eigen::Vector2d & eeVel ) const
inline

Calculates the joint velocity that yields the desired EE velocity.

Parameters
jointPosThe current joint angles.
eeVelThe desired EE velocity.
Returns
navtypes::Vectord<N> The joint velocities that yields the desired EE velocity.

◆ getJacobian()

template<unsigned int D, unsigned int N>
virtual navtypes::Matrixd< D, N > kinematics::ForwardArmKinematics< D, N >::getJacobian ( const navtypes::Vectord< N > & jointPos) const
pure virtual

Get the jacobian matrix for the arm at the given joint angles.

Parameters
jointPosThe joint angles of the arm.
Returns
navtypes::Matrixd<D, N> The jacobian matrix at the point.
See also
https://en.wikipedia.org/wiki/Jacobian_matrix_and_determinant

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

◆ getNumDimensions()

template<unsigned int D, unsigned int N>
unsigned int kinematics::ForwardArmKinematics< D, N >::getNumDimensions ( ) const
inlineconstexpr

Get the number of dimensions of the end effector space.

Returns
constexpr unsigned int The number of dimensions.

◆ getNumSegments()

template<unsigned int D, unsigned int N>
unsigned int kinematics::ForwardArmKinematics< D, N >::getNumSegments ( ) const
inlineconstexpr

Get the number of segments in this arm.

Returns
constexpr unsigned int The number of segments.

◆ getSegLens()

template<unsigned int D, unsigned int N>
virtual navtypes::Vectord< N > kinematics::ForwardArmKinematics< D, N >::getSegLens ( ) const
pure virtual

Get the segment lengths for this arm.

Returns
The vector of segment lengths

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

◆ jointPosToEEPos()

template<unsigned int D, unsigned int N>
virtual navtypes::Vectord< D > kinematics::ForwardArmKinematics< D, N >::jointPosToEEPos ( const navtypes::Vectord< N > & jointPos) const
pure virtual

Given a joint position, calculate the current EE position.

Parameters
jointPosCurrent joint position.
Returns
navtypes::Vectord<D> The EE position.

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

◆ jointVelToEEVel()

template<unsigned int D, unsigned int N>
navtypes::Vectord< D > kinematics::ForwardArmKinematics< D, N >::jointVelToEEVel ( const navtypes::Vectord< N > & jointPos,
const navtypes::Vectord< N > & jointVel ) const
inline

Calculate the EE velocity.

Parameters
jointPosCurrent joint position.
jointVelCurrent velocity of each joint angle.
Returns
navtypes::Vectord<D> The EE velocity.

◆ satisfiesConstraints()

template<unsigned int D, unsigned int N>
virtual bool kinematics::ForwardArmKinematics< D, N >::satisfiesConstraints ( const navtypes::Vectord< N > & jointPos) const
pure virtual

Check if the given joint configuration is valid.

Parameters
jointPosThe joint positions to check.
Returns
true iff the joint configuration is valid, false otherwise.

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


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