Converts a hyq foot position to joint angles.  
 More...
#include <hyqleg_inverse_kinematics.h>
Converts a hyq foot position to joint angles. 
Definition at line 42 of file hyqleg_inverse_kinematics.h.
  
  | 
        
          | xpp::HyqlegInverseKinematics::HyqlegInverseKinematics | ( |  | ) |  |  | default | 
 
Default c'tor initializing leg lengths with standard values. 
 
 
  
  | 
        
          | virtual xpp::HyqlegInverseKinematics::~HyqlegInverseKinematics | ( |  | ) |  |  | virtualdefault | 
 
 
      
        
          | 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. |  | joint | Which joint (HAA, HFE, KFE) this value represents. |  
 
Definition at line 119 of file hyqleg_inverse_kinematics.cc.
 
 
Returns the joint angles to reach a Cartesian foot position. 
- Parameters
- 
  
    | ee_pos_H | Foot position xyz expressed in the frame attached at the hip-aa (H). |  
 
Definition at line 42 of file hyqleg_inverse_kinematics.cc.
 
 
  
  | 
        
          | double xpp::HyqlegInverseKinematics::length_shank = 0.33 |  | private | 
 
 
  
  | 
        
          | double xpp::HyqlegInverseKinematics::length_thigh = 0.35 |  | private | 
 
 
The documentation for this class was generated from the following files: