Inverse kinematics function for the HyQ robot. More...
#include <inverse_kinematics_hyq4.h>

| Public Member Functions | |
| Joints | GetAllJointAngles (const EndeffectorsPos &pos_b) const override | 
| Returns joint angles to reach for a specific foot position.  More... | |
| int | GetEECount () const override | 
| Number of endeffectors (feet, hands) this implementation expects.  More... | |
| InverseKinematicsHyq4 ()=default | |
| virtual | ~InverseKinematicsHyq4 ()=default | 
|  Public Member Functions inherited from xpp::InverseKinematics | |
| InverseKinematics ()=default | |
| virtual | ~InverseKinematics ()=default | 
| Private Attributes | |
| Vector3d | base2hip_LF_ = Vector3d(0.3735, 0.207, 0.0) | 
| HyqlegInverseKinematics | leg | 
| Additional Inherited Members | |
|  Public Types inherited from xpp::InverseKinematics | |
| typedef std::shared_ptr< InverseKinematics > | Ptr | 
| typedef Eigen::Vector3d | Vector3d | 
Inverse kinematics function for the HyQ robot.
Definition at line 41 of file inverse_kinematics_hyq4.h.
| 
 | default | 
| 
 | virtualdefault | 
| 
 | overridevirtual | 
Returns joint angles to reach for a specific foot position.
| pos_B | 3D-position of the foot expressed in the base frame (B). | 
Implements xpp::InverseKinematics.
Definition at line 38 of file inverse_kinematics_hyq4.cc.
| 
 | inlineoverridevirtual | 
Number of endeffectors (feet, hands) this implementation expects.
Implements xpp::InverseKinematics.
Definition at line 55 of file inverse_kinematics_hyq4.h.
Definition at line 58 of file inverse_kinematics_hyq4.h.
| 
 | private | 
Definition at line 59 of file inverse_kinematics_hyq4.h.