Public Types | Public Member Functions | Private Attributes | List of all members
xpp::HyqlegInverseKinematics Class Reference

Converts a hyq foot position to joint angles. More...

#include <hyqleg_inverse_kinematics.h>

Public Types

enum  KneeBend { Forward, Backward }
 
using Vector3d = Eigen::Vector3d
 

Public Member Functions

void EnforceLimits (double &q, HyqJointID joint) const
 Restricts the joint angles to lie inside the feasible range. More...
 
Vector3d GetJointAngles (const Vector3d &ee_pos_H, KneeBend bend=Forward) const
 Returns the joint angles to reach a Cartesian foot position. More...
 
 HyqlegInverseKinematics ()=default
 Default c'tor initializing leg lengths with standard values. More...
 
virtual ~HyqlegInverseKinematics ()=default
 

Private Attributes

Vector3d hfe_to_haa_z = Vector3d(0.0, 0.0, 0.08)
 
double length_shank = 0.33
 
double length_thigh = 0.35
 

Detailed Description

Converts a hyq foot position to joint angles.

Definition at line 42 of file hyqleg_inverse_kinematics.h.

Member Typedef Documentation

using xpp::HyqlegInverseKinematics::Vector3d = Eigen::Vector3d

Definition at line 44 of file hyqleg_inverse_kinematics.h.

Member Enumeration Documentation

Enumerator
Forward 
Backward 

Definition at line 45 of file hyqleg_inverse_kinematics.h.

Constructor & Destructor Documentation

xpp::HyqlegInverseKinematics::HyqlegInverseKinematics ( )
default

Default c'tor initializing leg lengths with standard values.

virtual xpp::HyqlegInverseKinematics::~HyqlegInverseKinematics ( )
virtualdefault

Member Function Documentation

void xpp::HyqlegInverseKinematics::EnforceLimits ( double &  q,
HyqJointID  joint 
) const

Restricts the joint angles to lie inside the feasible range.

Parameters
q[in/out]Current joint angle that is adapted if it exceeds the specified range.
jointWhich joint (HAA, HFE, KFE) this value represents.

Definition at line 119 of file hyqleg_inverse_kinematics.cc.

HyqlegInverseKinematics::Vector3d xpp::HyqlegInverseKinematics::GetJointAngles ( const Vector3d ee_pos_H,
KneeBend  bend = Forward 
) const

Returns the joint angles to reach a Cartesian foot position.

Parameters
ee_pos_HFoot position xyz expressed in the frame attached at the hip-aa (H).

Definition at line 42 of file hyqleg_inverse_kinematics.cc.

Member Data Documentation

Vector3d xpp::HyqlegInverseKinematics::hfe_to_haa_z = Vector3d(0.0, 0.0, 0.08)
private

Definition at line 69 of file hyqleg_inverse_kinematics.h.

double xpp::HyqlegInverseKinematics::length_shank = 0.33
private

Definition at line 71 of file hyqleg_inverse_kinematics.h.

double xpp::HyqlegInverseKinematics::length_thigh = 0.35
private

Definition at line 70 of file hyqleg_inverse_kinematics.h.


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


xpp_hyq
Author(s): Alexander W. Winkler, Diego Pardo. , Carlos Mastalli , Ioannis Havoutis
autogenerated on Tue Dec 8 2020 03:10:35