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

#include <JointPathEx.h>

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

Public Member Functions

bool calcInverseKinematics2 (const Vector3 &end_p, const Matrix33 &end_R, const double avoid_gain=0.0, const double reference_gain=0.0, const dvector *reference_q=NULL)
 
bool calcInverseKinematics2Loop (const Vector3 &dp, const Vector3 &omega, const double LAMBDA, const double avoid_gain=0.0, const double reference_gain=0.0, const dvector *reference_q=NULL)
 
bool calcInverseKinematics2Loop (const Vector3 &end_effector_p, const Matrix33 &end_effector_R, const double LAMBDA, const double avoid_gain=0.0, const double reference_gain=0.0, const hrp::dvector *reference_q=NULL, const double vel_gain=1.0, const hrp::Vector3 &localPos=hrp::Vector3::Zero(), const hrp::Matrix33 &localR=hrp::Matrix33::Identity())
 
bool calcJacobianInverseNullspace (dmatrix &J, dmatrix &Jinv, dmatrix &Jnull)
 
void getInterlockingJointPairIndices (std::vector< std::pair< size_t, size_t > > &pairs)
 
double getManipulabilityLimit ()
 
void getOptionalWeightVector (std::vector< double > &_opt_w)
 
double getSRGain ()
 
 JointPathEx (BodyPtr &robot, Link *base, Link *end, double control_cycle, bool _use_inside_joint_weight_retrieval=true, const std::string &_debug_print_prefix="")
 
bool setInterlockingJointPairIndices (const std::vector< std::pair< Link *, Link * > > &pairs, const std::string &print_str="")
 
bool setInterlockingJointPairIndices (const std::vector< std::pair< size_t, size_t > > &pairs)
 
bool setManipulabilityGain (double l)
 
bool setManipulabilityLimit (double l)
 
void setMaxIKError (double epos, double erot)
 
void setMaxIKError (double e)
 
void setMaxIKIteration (int iter)
 
void setOptionalWeightVector (const std::vector< double > &_opt_w)
 
bool setSRGain (double g)
 
- Public Member Functions inherited from hrp::JointPath
LinkbaseLink () const
 
void calcForwardKinematics (bool calcVelocity=false, bool calcAcceleration=false) const
 
bool calcInverseKinematics (const Vector3 &base_p, const Matrix33 &base_R, const Vector3 &end_p, const Matrix33 &end_R)
 
virtual bool calcInverseKinematics (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 ~JointPath ()
 
- Public Member Functions inherited from hrp::InverseKinematics
virtual ~InverseKinematics ()
 

Protected Attributes

std::vector< double > avoid_weight_gain
 
size_t debug_print_freq_count
 
std::string debug_print_prefix
 
double dt
 
std::vector< std::pair< size_t, size_t > > interlocking_joint_pair_indices
 
std::vector< size_t > joint_limit_debug_print_counts
 
std::vector< Link * > joints
 
double manipulability_gain
 
double manipulability_limit
 
int maxIKIteration
 
double maxIKPosErrorSqr
 
double maxIKRotErrorSqr
 
std::vector< double > optional_weight_vector
 
double sr_gain
 
bool use_inside_joint_weight_retrieval
 
- Protected Attributes inherited from hrp::JointPath
bool isBestEffortIKMode
 
double maxIKErrorSqr
 

Additional Inherited Members

- Protected Member Functions inherited from hrp::JointPath
virtual void onJointPathUpdated ()
 

Detailed Description

Definition at line 16 of file JointPathEx.h.

Constructor & Destructor Documentation

JointPathEx::JointPathEx ( BodyPtr robot,
Link base,
Link end,
double  control_cycle,
bool  _use_inside_joint_weight_retrieval = true,
const std::string &  _debug_print_prefix = "" 
)

Definition at line 92 of file JointPathEx.cpp.

Member Function Documentation

bool JointPathEx::calcInverseKinematics2 ( const Vector3 end_p,
const Matrix33 end_R,
const double  avoid_gain = 0.0,
const double  reference_gain = 0.0,
const dvector reference_q = NULL 
)

Definition at line 473 of file JointPathEx.cpp.

bool JointPathEx::calcInverseKinematics2Loop ( const Vector3 dp,
const Vector3 omega,
const double  LAMBDA,
const double  avoid_gain = 0.0,
const double  reference_gain = 0.0,
const dvector reference_q = NULL 
)

Definition at line 237 of file JointPathEx.cpp.

bool JointPathEx::calcInverseKinematics2Loop ( const Vector3 end_effector_p,
const Matrix33 end_effector_R,
const double  LAMBDA,
const double  avoid_gain = 0.0,
const double  reference_gain = 0.0,
const hrp::dvector reference_q = NULL,
const double  vel_gain = 1.0,
const hrp::Vector3 localPos = hrp::Vector3::Zero(),
const hrp::Matrix33 localR = hrp::Matrix33::Identity() 
)

Definition at line 457 of file JointPathEx.cpp.

bool JointPathEx::calcJacobianInverseNullspace ( dmatrix J,
dmatrix Jinv,
dmatrix Jnull 
)

Definition at line 160 of file JointPathEx.cpp.

void JointPathEx::getInterlockingJointPairIndices ( std::vector< std::pair< size_t, size_t > > &  pairs)

Definition at line 156 of file JointPathEx.cpp.

double hrp::JointPathEx::getManipulabilityLimit ( )
inline

Definition at line 28 of file JointPathEx.h.

void hrp::JointPathEx::getOptionalWeightVector ( std::vector< double > &  _opt_w)
inline

Definition at line 43 of file JointPathEx.h.

double hrp::JointPathEx::getSRGain ( )
inline

Definition at line 26 of file JointPathEx.h.

bool JointPathEx::setInterlockingJointPairIndices ( const std::vector< std::pair< Link *, Link * > > &  pairs,
const std::string &  print_str = "" 
)

Definition at line 121 of file JointPathEx.cpp.

bool JointPathEx::setInterlockingJointPairIndices ( const std::vector< std::pair< size_t, size_t > > &  pairs)

Definition at line 151 of file JointPathEx.cpp.

bool hrp::JointPathEx::setManipulabilityGain ( double  l)
inline

Definition at line 30 of file JointPathEx.h.

bool hrp::JointPathEx::setManipulabilityLimit ( double  l)
inline

Definition at line 29 of file JointPathEx.h.

void JointPathEx::setMaxIKError ( double  epos,
double  erot 
)

Definition at line 107 of file JointPathEx.cpp.

void JointPathEx::setMaxIKError ( double  e)
virtual

Reimplemented from hrp::JointPath.

Definition at line 112 of file JointPathEx.cpp.

void JointPathEx::setMaxIKIteration ( int  iter)

Definition at line 117 of file JointPathEx.cpp.

void hrp::JointPathEx::setOptionalWeightVector ( const std::vector< double > &  _opt_w)
inline

Definition at line 34 of file JointPathEx.h.

bool hrp::JointPathEx::setSRGain ( double  g)
inline

Definition at line 27 of file JointPathEx.h.

Member Data Documentation

std::vector<double> hrp::JointPathEx::avoid_weight_gain
protected

Definition at line 53 of file JointPathEx.h.

size_t hrp::JointPathEx::debug_print_freq_count
protected

Definition at line 63 of file JointPathEx.h.

std::string hrp::JointPathEx::debug_print_prefix
protected

Definition at line 60 of file JointPathEx.h.

double hrp::JointPathEx::dt
protected

Definition at line 59 of file JointPathEx.h.

std::vector<std::pair<size_t, size_t> > hrp::JointPathEx::interlocking_joint_pair_indices
protected

Definition at line 58 of file JointPathEx.h.

std::vector<size_t> hrp::JointPathEx::joint_limit_debug_print_counts
protected

Definition at line 62 of file JointPathEx.h.

std::vector<Link*> hrp::JointPathEx::joints
protected

Definition at line 52 of file JointPathEx.h.

double hrp::JointPathEx::manipulability_gain
protected

Definition at line 59 of file JointPathEx.h.

double hrp::JointPathEx::manipulability_limit
protected

Definition at line 59 of file JointPathEx.h.

int hrp::JointPathEx::maxIKIteration
protected

Definition at line 51 of file JointPathEx.h.

double hrp::JointPathEx::maxIKPosErrorSqr
protected

Definition at line 48 of file JointPathEx.h.

double hrp::JointPathEx::maxIKRotErrorSqr
protected

Definition at line 48 of file JointPathEx.h.

std::vector<double> hrp::JointPathEx::optional_weight_vector
protected

Definition at line 53 of file JointPathEx.h.

double hrp::JointPathEx::sr_gain
protected

Definition at line 59 of file JointPathEx.h.

bool hrp::JointPathEx::use_inside_joint_weight_retrieval
protected

Definition at line 64 of file JointPathEx.h.


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


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Thu May 6 2021 02:41:53