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 |
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.
using xpp::InverseKinematics::Ptr = std::shared_ptr<InverseKinematics> |
Definition at line 50 of file inverse_kinematics.h.
using xpp::InverseKinematics::Vector3d = Eigen::Vector3d |
Definition at line 51 of file inverse_kinematics.h.
|
default |
|
virtualdefault |
|
pure virtual |
Calculates the joint angles to reach a position @ pos_b.
pos_b | 3D-position of the endeffector expressed in base frame. |
|
pure virtual |
Number of endeffectors (feet, hands) this implementation expects.