|
Resurgence (PY2022)
Codebase for the Husky Robotics 2021-2022 rover Resurgence
|
A class that calculates the forward kinematics of an arm. More...
#include <ForwardArmKinematics.h>

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. | |
A class that calculates the forward kinematics of an arm.
| D | The number of dimensions of the end effector space. |
| N | The number of joints in the arm. |
|
inline |
Calculates the joint velocity that yields the desired EE velocity.
| jointPos | The current joint angles. |
| eeVel | The desired EE velocity. |
|
pure virtual |
Get the jacobian matrix for the arm at the given joint angles.
| jointPos | The joint angles of the arm. |
Implemented in kinematics::ArmKinematics< D, N >, kinematics::ArmKinematics< 2, N >, and kinematics::PlanarArmFK< N >.
|
inlineconstexpr |
Get the number of dimensions of the end effector space.
|
inlineconstexpr |
Get the number of segments in this arm.
|
pure virtual |
Get the segment lengths for this arm.
Implemented in kinematics::ArmKinematics< D, N >, kinematics::ArmKinematics< 2, N >, and kinematics::PlanarArmFK< N >.
|
pure virtual |
Given a joint position, calculate the current EE position.
| jointPos | Current joint position. |
Implemented in kinematics::ArmKinematics< D, N >, kinematics::ArmKinematics< 2, N >, and kinematics::PlanarArmFK< N >.
|
inline |
Calculate the EE velocity.
| jointPos | Current joint position. |
| jointVel | Current velocity of each joint angle. |
|
pure virtual |
Check if the given joint configuration is valid.
| jointPos | The joint positions to check. |
Implemented in kinematics::ArmKinematics< D, N >, kinematics::ArmKinematics< 2, N >, and kinematics::PlanarArmFK< N >.