Public Types | Public Member Functions | List of all members
xpp::InverseKinematics Class Referenceabstract

Converts Cartesian endeffector positions into joint angles. More...

#include <inverse_kinematics.h>

Public Types

using Ptr = std::shared_ptr< InverseKinematics >
 
using Vector3d = Eigen::Vector3d
 

Public Member Functions

virtual Joints GetAllJointAngles (const EndeffectorsPos &pos_b) const =0
 Calculates the joint angles to reach a position @ pos_b. More...
 
virtual int GetEECount () const =0
 Number of endeffectors (feet, hands) this implementation expects. More...
 
 InverseKinematics ()=default
 
virtual ~InverseKinematics ()=default
 

Detailed Description

Converts Cartesian endeffector positions into joint angles.

This class is responsible for calculating the joint angles of a robot given an endeffector position (=inverse kinematics). Base class that every inverse dynamics class must conform with.

Definition at line 48 of file inverse_kinematics.h.

Member Typedef Documentation

Definition at line 50 of file inverse_kinematics.h.

using xpp::InverseKinematics::Vector3d = Eigen::Vector3d

Definition at line 51 of file inverse_kinematics.h.

Constructor & Destructor Documentation

xpp::InverseKinematics::InverseKinematics ( )
default
virtual xpp::InverseKinematics::~InverseKinematics ( )
virtualdefault

Member Function Documentation

virtual Joints xpp::InverseKinematics::GetAllJointAngles ( const EndeffectorsPos pos_b) const
pure virtual

Calculates the joint angles to reach a position @ pos_b.

Parameters
pos_b3D-position of the endeffector expressed in base frame.
Returns
Joints angles of the robot.
virtual int xpp::InverseKinematics::GetEECount ( ) const
pure virtual

Number of endeffectors (feet, hands) this implementation expects.


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


xpp_vis
Author(s): Alexander W. Winkler
autogenerated on Tue Dec 8 2020 03:10:32