Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
hrp::JointPath Class Reference

#include <JointPath.h>

Inheritance diagram for hrp::JointPath:
Inheritance graph
[legend]

Public Member Functions

LinkbaseLink () const
 
void calcForwardKinematics (bool calcVelocity=false, bool calcAcceleration=false) const
 
virtual bool calcInverseKinematics (const Vector3 &end_p, const Matrix33 &end_R)
 
bool calcInverseKinematics (const Vector3 &base_p, const Matrix33 &base_R, const Vector3 &end_p, const Matrix33 &end_R)
 
void calcJacobian (dmatrix &out_J, const Vector3 &local_p=Vector3::Zero()) const
 
void calcJacobianDot (dmatrix &out_dJ, const Vector3 &local_p=Vector3::Zero()) const
 
bool empty () const
 
LinkendLink () const
 
bool find (Link *base, Link *end)
 
bool find (Link *end)
 
virtual bool hasAnalyticalIK ()
 
bool isJointDownward (int index) const
 
dmatrix Jacobian () const
 
Linkjoint (int index) const
 
 JointPath ()
 
 JointPath (Link *base, Link *end)
 
 JointPath (Link *end)
 
unsigned int numJoints () const
 
virtual void setBestEffortIKMode (bool on)
 
virtual void setMaxIKError (double e)
 
virtual ~JointPath ()
 
- Public Member Functions inherited from hrp::InverseKinematics
virtual ~InverseKinematics ()
 

Protected Member Functions

virtual void onJointPathUpdated ()
 

Protected Attributes

bool isBestEffortIKMode
 
double maxIKErrorSqr
 

Private Member Functions

void extractJoints ()
 
void initialize ()
 

Private Attributes

std::vector< Link * > joints
 
LinkPath linkPath
 
int numUpwardJointConnections
 

Detailed Description

Definition at line 26 of file JointPath.h.

Constructor & Destructor Documentation

JointPath::JointPath ( )

Definition at line 25 of file JointPath.cpp.

JointPath::JointPath ( Link base,
Link end 
)

Definition at line 31 of file JointPath.cpp.

JointPath::JointPath ( Link end)

Definition at line 40 of file JointPath.cpp.

JointPath::~JointPath ( )
virtual

Definition at line 56 of file JointPath.cpp.

Member Function Documentation

Link* hrp::JointPath::baseLink ( ) const
inline

Definition at line 50 of file JointPath.h.

void hrp::JointPath::calcForwardKinematics ( bool  calcVelocity = false,
bool  calcAcceleration = false 
) const
inline

Definition at line 62 of file JointPath.h.

bool JointPath::calcInverseKinematics ( const Vector3 end_p,
const Matrix33 end_R 
)
virtual

Implements hrp::InverseKinematics.

Reimplemented in hrp::CustomizedJointPath.

Definition at line 252 of file JointPath.cpp.

bool JointPath::calcInverseKinematics ( const Vector3 base_p,
const Matrix33 base_R,
const Vector3 end_p,
const Matrix33 end_R 
)

Definition at line 238 of file JointPath.cpp.

void JointPath::calcJacobian ( dmatrix out_J,
const Vector3 local_p = Vector3::Zero() 
) const

Definition at line 128 of file JointPath.cpp.

void JointPath::calcJacobianDot ( dmatrix out_dJ,
const Vector3 local_p = Vector3::Zero() 
) const

Definition at line 173 of file JointPath.cpp.

bool hrp::JointPath::empty ( void  ) const
inline

Definition at line 38 of file JointPath.h.

Link* hrp::JointPath::endLink ( ) const
inline

Definition at line 54 of file JointPath.h.

void JointPath::extractJoints ( )
private

Definition at line 83 of file JointPath.cpp.

bool JointPath::find ( Link base,
Link end 
)

Definition at line 62 of file JointPath.cpp.

bool JointPath::find ( Link end)

Definition at line 73 of file JointPath.cpp.

bool JointPath::hasAnalyticalIK ( )
virtual

Reimplemented in hrp::CustomizedJointPath.

Definition at line 341 of file JointPath.cpp.

void JointPath::initialize ( void  )
private

Definition at line 49 of file JointPath.cpp.

bool hrp::JointPath::isJointDownward ( int  index) const
inline

Definition at line 58 of file JointPath.h.

dmatrix hrp::JointPath::Jacobian ( ) const
inline

Definition at line 68 of file JointPath.h.

Link* hrp::JointPath::joint ( int  index) const
inline

Definition at line 46 of file JointPath.h.

unsigned int hrp::JointPath::numJoints ( ) const
inline

Definition at line 42 of file JointPath.h.

void JointPath::onJointPathUpdated ( )
protectedvirtual

Reimplemented in hrp::CustomizedJointPath.

Definition at line 122 of file JointPath.cpp.

void JointPath::setBestEffortIKMode ( bool  on)
virtual

Definition at line 231 of file JointPath.cpp.

void JointPath::setMaxIKError ( double  e)
virtual

Definition at line 225 of file JointPath.cpp.

Member Data Documentation

bool hrp::JointPath::isBestEffortIKMode
protected

Definition at line 90 of file JointPath.h.

std::vector<Link*> hrp::JointPath::joints
private

Definition at line 98 of file JointPath.h.

LinkPath hrp::JointPath::linkPath
private

Definition at line 97 of file JointPath.h.

double hrp::JointPath::maxIKErrorSqr
protected

Definition at line 89 of file JointPath.h.

int hrp::JointPath::numUpwardJointConnections
private

Definition at line 99 of file JointPath.h.


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


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Sat May 8 2021 02:42:45