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

Kinematics object for a sequence of arm segments in a 2d plane. More...

#include <PlanarArmFK.h>

Inheritance diagram for kinematics::PlanarArmFK< N >:
Collaboration diagram for kinematics::PlanarArmFK< N >:

Public Member Functions

 PlanarArmFK (const navtypes::Vectord< N > &segLens, const navtypes::Vectord< N > &jointMin, const navtypes::Vectord< N > &jointMax)
 Construct a new kinematics object.
 
navtypes::Vectord< N > getSegLens () const override
 Get the segment lengths for this arm.
 
bool satisfiesConstraints (const navtypes::Vectord< N > &jointPos) const override
 Check if the given joint configuration is valid.
 
navtypes::Matrixd< 2, N > getJacobian (const navtypes::Vectord< N > &jointPos) const override
 Get the jacobian matrix for the arm at the given joint angles.
 
Eigen::Vector2d jointPosToEEPos (const navtypes::Vectord< N > &jointPos) const override
 Given a joint position, calculate the current EE position.
 
- Public Member Functions inherited from kinematics::ForwardArmKinematics< 2, N >
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.
 

Detailed Description

template<unsigned int N>
class kinematics::PlanarArmFK< N >

Kinematics object for a sequence of arm segments in a 2d plane.

Template Parameters
NThe number of joints.

Constructor & Destructor Documentation

◆ PlanarArmFK()

template<unsigned int N>
kinematics::PlanarArmFK< N >::PlanarArmFK ( const navtypes::Vectord< N > & segLens,
const navtypes::Vectord< N > & jointMin,
const navtypes::Vectord< N > & jointMax )
inline

Construct a new kinematics object.

Parameters
segLensThe length of each arm segment.
jointMinThe minimum angle of each joint. Set to -pi for no limit.
jointMaxThe maximum angle of each joint. Set to pi for no limit.

Member Function Documentation

◆ getJacobian()

template<unsigned int N>
navtypes::Matrixd< 2, N > kinematics::PlanarArmFK< N >::getJacobian ( const navtypes::Vectord< N > & jointPos) const
inlineoverridevirtual

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

Implements kinematics::ForwardArmKinematics< 2, N >.

◆ getSegLens()

template<unsigned int N>
navtypes::Vectord< N > kinematics::PlanarArmFK< N >::getSegLens ( ) const
inlineoverridevirtual

Get the segment lengths for this arm.

Returns
The vector of segment lengths

Implements kinematics::ForwardArmKinematics< 2, N >.

◆ jointPosToEEPos()

template<unsigned int N>
Eigen::Vector2d kinematics::PlanarArmFK< N >::jointPosToEEPos ( const navtypes::Vectord< N > & jointPos) const
inlineoverridevirtual

Given a joint position, calculate the current EE position.

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

Implements kinematics::ForwardArmKinematics< 2, N >.

◆ satisfiesConstraints()

template<unsigned int N>
bool kinematics::PlanarArmFK< N >::satisfiesConstraints ( const navtypes::Vectord< N > & jointPos) const
inlineoverridevirtual

Check if the given joint configuration is valid.

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

Implements kinematics::ForwardArmKinematics< 2, N >.


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