Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
IK Class Reference

Main class for inverse kinematic computation. More...

#include <ik.h>

Inheritance diagram for IK:
Inheritance graph
[legend]

Public Types

enum  ConstIndex { HAVE_CONSTRAINT, NO_CONSTRAINT }
 
enum  ConstType {
  HANDLE_CONSTRAINT, DESIRE_CONSTRAINT, COM_CONSTRAINT, SCALAR_JOINT_LIMIT_CONSTRAINT,
  IK_NUM_CONSTRAINT_TYPES
}
 
enum  Priority { HIGH_PRIORITY = 0, HIGH_IF_POSSIBLE, LOW_PRIORITY, N_PRIORITY_TYPES }
 

Public Member Functions

int AddConstraint (IKConstraint *_constraint)
 
IKHandleAddMarker (const std::string &label, const std::string &linkname, const std::string &charname, const fVec3 &rel_pos)
 Add new marker constraint. More...
 
IKHandleAddMarker (const char *marker_name, Joint *parent_joint, const fVec3 &abs_pos=0.0)
 
int ConstraintID (ConstType _type, const char *jname)
 
int ConstraintID (int _index)
 
int ConstraintIndex (ConstType _type, const char *jname)
 
int ConstraintIndex (int _id)
 
int DisableDesire (const char *jname)
 Disable desire constraint of the specific joint. More...
 
int EditMarker (IKHandle *marker, const char *body_name, Joint *parent_joint, const fVec3 &abs_pos=0.0)
 
int EnableDesire (const char *jname)
 Enable desire constraint of the specific joint. More...
 
IKConstraintFindConstraint (ConstType _type, const char *jname, const char *charname=0)
 
IKConstraintFindConstraint (int _id)
 
double GetMaxConditionNumber ()
 Get maximum condition number. More...
 
 IK ()
 Default constructor. More...
 
int LoadMarkerXML (const char *fname, const char *_charname)
 Load marker information from XML file. More...
 
int NumConstraints ()
 Number of constraints. More...
 
int NumConstraints (ConstType t)
 Number of constraints with specific type. More...
 
int RemoveAllConstraints ()
 
int RemoveConstraint (int _id)
 
int ResetAllConstraints ()
 Reset all constraints. More...
 
int ResetConstraints (ConstType t)
 Reset the constraints with the specific type. More...
 
int SaveMarkers (const char *fname)
 
void SetCharacterScale (double _scale, const char *charname=0)
 Set character scale parameter. More...
 
void SetConstraintScale (double _scale, const char *charname=0)
 Set constraint scale parameter. More...
 
int SetDesireGain (const char *jname, double _gain)
 Set gain of desire constraint of the specific joint. More...
 
int SetJointWeight (const char *jname, double _weight)
 Set joint weight, for single-DOF joints. More...
 
int SetJointWeight (const char *jname, const fVec &_weight)
 Set joint weight, for multiple-DOF joints. More...
 
void SetMaxConditionNumber (double cn)
 Set maximum condition number. More...
 
double Update (double timestep)
 
double Update (double max_timestep, double min_timestep, double max_integ_error=DEFAULT_MAX_INTEG_ERROR)
 Perform inverse kinematics with adaptive time step. More...
 
 ~IK ()
 Destructor. More...
 
- Public Member Functions inherited from Chain
void add_scale_object (const scale_object &_s)
 
int AddJoint (Joint *target, Joint *p)
 Add a new joint target as a child of joint p. More...
 
int AddJoint (Joint *target, const char *parent_name, const char *charname=0)
 Add a new joint target as a child of joint with name parent_name. More...
 
JointAddJoint (JointData *joint_data, const char *charname=0)
 Create and add a joint using JointData structure. More...
 
JointAddRoot (const char *name=0, const fVec3 &grav=fVec3(0.0, 0.0, 9.8))
 Add the (unique) root joint. More...
 
int AddRoot (Joint *r)
 Add the (unique) root joint. More...
 
void ApplyGeomScale (SceneGraph *sg)
 
int BeginCreateChain (int append=false)
 Indicates begining of creating a kinematic chain. More...
 
void CalcAcceleration ()
 
void CalcPosition ()
 Forward kinematics. More...
 
void CalcVelocity ()
 
 Chain ()
 
virtual void Clear ()
 Remove all joints and clear all parameters. More...
 
void clear_scale_object_list ()
 
int ClearExtForce ()
 Clear the external forces/torques. More...
 
int ClearJointForce ()
 Clear the joint forces/torques. More...
 
double ComJacobian (fMat &J, fVec3 &com, const char *chname=0)
 Computes the com Jacobian. More...
 
int Connect (Joint *virtual_joint, Joint *parent_joint)
 Connect two links by adding a new virtual joint. More...
 
int CreateParallel (int num_char, const char *prmname, const char *charname, const fVec3 &init_pos=0.0, const fMat33 &init_att=1.0, const fVec3 &pos_offset=0.0, const fMat33 &att_offset=1.0, int init_num=0)
 Automatically generate multiple identical chains. More...
 
int CreateSerial (int num_joint, const JointData &joint_data, const char *charname=0, Joint *parent_joint=0)
 Automatically generate a serial chain. More...
 
int Disconnect (Joint *j)
 Disconnect the loop at the specified virtual joint. More...
 
int EndCreateChain (SceneGraph *sg=NULL)
 End editing a chain. More...
 
JointFindCharacterRoot (const char *charname)
 Find the root joint of the character with name charname. More...
 
JointFindJoint (const char *jname, const char *charname=0)
 Find a joint from name. More...
 
JointFindJoint (int _id)
 Find a joint with ID _id. More...
 
int GetJointAcc (fVec &accs)
 
int GetJointForce (fVec &forces)
 Obtain the joint forces/torques. More...
 
int GetJointList (Joint **&joints)
 Obtain a list of pointers to all joints. More...
 
int GetJointNameList (char **&jnames)
 Obtain a list of joint names. More...
 
int GetJointValue (fVec &values)
 Obtain the joint values/velocities/accelerations. More...
 
int GetJointVel (fVec &vels)
 
int Integrate (double timestep)
 Performs Euler integration with timestep timestep [s]. More...
 
int IntegrateAdaptive (double &timestep, int step, double min_timestep=DEFAULT_MIN_TIMESTEP, double max_integ_error=DEFAULT_MAX_INTEG_ERROR)
 Performs Euler integration with adaptive timestep. More...
 
int IntegrateRK4 (double timestep, int step)
 Performs 4-th order Runge-Kutta integration. More...
 
int IntegrateRK4Value (double timestep, int step)
 
int IntegrateRK4Velocity (double timestep, int step)
 
int IntegrateValue (double timestep)
 Integrate value/velocity only. More...
 
int IntegrateVelocity (double timestep)
 
void InvDyn (fVec &tau)
 Inverse dynamics. More...
 
int Load (const char *fname, const char *charname=0)
 Load the chain from a file in original (*.prm) format. More...
 
int LoadXML (const char *fname, const char *charname=0)
 Load the chain from an XML file. More...
 
int NumDOF ()
 Total degrees of freedom. More...
 
int NumJoint ()
 Total number of joints. More...
 
int NumValue ()
 Dimension of the joint value vector (using Euler parameter representation for orientation). More...
 
int RemoveJoint (Joint *j)
 disconnect joint j from its parent More...
 
JointRoot ()
 
int Save (const char *fname, const char *charname=0) const
 Save the chain data to a file in original (*.prm) format. More...
 
int Save (ostream &ost, const char *charname=0) const
 
int SaveStatus (fVec &value, fVec &vel, fVec &acc)
 Save current joint values, velocities, and accelerations. More...
 
int SaveXML (const char *fname, const char *charname=0) const
 Save the chain data to a file in XML format. More...
 
int SaveXML (ostream &ost, const char *charname=0) const
 
int set_abs_position_orientation (Joint *jnt, const fVec3 &abs_pos, const fMat33 &abs_att)
 
int SetAllTorqueGiven (int _tg)
 Change torque/motion control property of all joints. More...
 
int SetCharacterTorqueGiven (const char *charname, int _tg)
 Change torque/motion control property of a character. More...
 
int SetJointAcc (const fVec &accs)
 
int SetJointForce (const fVec &forces)
 Set all joint forces/torques. More...
 
int SetJointValue (const fVec &values)
 Set all joint values. More...
 
int SetJointVel (const fVec &vels)
 Set all joint velocities/accelerations. More...
 
int SetStatus (const fVec &value, const fVec &vel, const fVec &acc)
 Set current joint values, velocities, and accelerations. More...
 
int SetTorqueGiven (Joint *_joint, int _tg)
 Change torque/motion control property of a joint. More...
 
double TotalCOM (fVec3 &com, const char *chname=0)
 Center of mass of the chain. More...
 
virtual ~Chain ()
 

Protected Member Functions

IKHandleadd_marker (const char *marker_name, Joint *parent_joint, const fVec3 &abs_pos)
 
IKHandleadd_marker (TransformNode *tn)
 
int assign_constraints (int _n)
 
int calc_feedback ()
 
int calc_jacobian ()
 compute the Jacobian matrix More...
 
int copy_jacobian ()
 
int edit_marker (IKHandle *marker, const char *body_name, Joint *parent_joint, const fVec3 &abs_pos)
 
int init (SceneGraph *sg)
 Initialize the parameters. More...
 
int load_markers (SceneGraph *sg, Joint *rj)
 
int load_markers (TransformNode *marker_top)
 
int myinit (SceneGraph *sg)
 
int save_marker (TransformNode *top_tnode, IKHandle *h)
 
void set_character_scale (Joint *jnt, double _scale, const char *charname)
 
double solve_ik ()
 compute the joint velocity More...
 
- Protected Member Functions inherited from Chain
void _apply_scale (Joint *jnt, double scale)
 
void apply_geom_scale (SceneGraph *sg, Joint *cur)
 
virtual void apply_scale ()
 
void apply_scale (const scale_object &_s)
 
void apply_scale_sub (Joint *cur, double scale)
 
void apply_scale_top (Joint *top, double scale)
 
void calc_abs_positions (Joint *cur, SceneGraph *sg)
 
void calc_rel_positions (Joint *cur, SceneGraph *sg)
 
virtual int clear_data ()
 Clear arrays only; don't delete joints. More...
 
void init_scale (SceneGraph *sg)
 
void init_scale_sub (Node *node)
 
void reset_scale ()
 
void reset_scale_sub (Joint *jnt)
 
void set_all_torque_given (Joint *cur, int _tg)
 
void set_relative_positions (SceneGraph *sg)
 

Protected Attributes

IKConstraint ** constraints
 list of current constraints More...
 
fVec fb [N_PRIORITY_TYPES]
 constraint error of each type More...
 
fMat J [N_PRIORITY_TYPES]
 Jacobian matrix of each type. More...
 
fVec joint_weights
 joint weights More...
 
double max_condnum
 maximum condition number More...
 
int n_all_const
 
int n_assigned_constraints
 
int n_const [N_PRIORITY_TYPES]
 number of constraints of each type More...
 
int n_constraints
 number of current constraints More...
 
int n_total_const
 number of total constraints used so far, including removed ones More...
 
fVec weight [N_PRIORITY_TYPES]
 weight of each type More...
 
- Protected Attributes inherited from Chain
double ** all_value
 Pointers to the integration variables. More...
 
double ** all_value_dot
 
double ** all_vel
 
double ** all_vel_dot
 
int do_connect
 true after Connect() was called; application (or subclass) must reset the flag More...
 
int in_create_chain
 true if between BeginCreateChain() and EndCreateChain(). More...
 
double * init_value
 
double * init_vel
 
double * j_acc_p [4]
 
double * j_value_dot [4]
 for 4-th order Runge-Kutta More...
 
int n_dof
 
int n_joint
 
int n_thrust
 total DOF of the joints with t_given = false More...
 
int n_value
 
Jointroot
 Chain information. More...
 
std::list< scale_objectscale_object_list
 

Friends

class IKConstraint
 
class IKDesire
 
class IKHandle
 

Detailed Description

Main class for inverse kinematic computation.

Definition at line 37 of file ik.h.

Member Enumeration Documentation

Enumerator
HAVE_CONSTRAINT 

with constraint

NO_CONSTRAINT 

without constraint

Definition at line 66 of file ik.h.

Enumerator
HANDLE_CONSTRAINT 

position/orientation of link

DESIRE_CONSTRAINT 

desired joint values

COM_CONSTRAINT 

center of mass position

SCALAR_JOINT_LIMIT_CONSTRAINT 

joint limit for rotate and slide joints

IK_NUM_CONSTRAINT_TYPES 

Definition at line 47 of file ik.h.

Enumerator
HIGH_PRIORITY 

strictly satisfied

HIGH_IF_POSSIBLE 

strictly satisfied if possible

LOW_PRIORITY 

lower priority

N_PRIORITY_TYPES 

Definition at line 57 of file ik.h.

Constructor & Destructor Documentation

IK::IK ( )

Default constructor.

Definition at line 17 of file ik.cpp.

IK::~IK ( )

Destructor.

Definition at line 29 of file ik.cpp.

Member Function Documentation

IKHandle * IK::add_marker ( const char *  marker_name,
Joint parent_joint,
const fVec3 abs_pos 
)
protected

Definition at line 282 of file ik.cpp.

IKHandle * IK::add_marker ( TransformNode *  tn)
protected

Definition at line 125 of file ik.cpp.

int IK::AddConstraint ( IKConstraint _constraint)

Add a new constraint.

Parameters
[in]_constraintpointer to the new constraint object
Returns
ID of the constraint

Definition at line 428 of file ik.cpp.

IKHandle * IK::AddMarker ( const std::string &  label,
const std::string &  linkname,
const std::string &  charname,
const fVec3 rel_pos 
)

Add new marker constraint.

Add new marker constraint.

Parameters
[in]labelmarker label
[in]linknamename of the link to which the marker is attached
[in]charnamecharacter name of the link
[in]rel_posposition of the marker in joint frame

Definition at line 244 of file ik.cpp.

IKHandle * IK::AddMarker ( const char *  marker_name,
Joint parent_joint,
const fVec3 abs_pos = 0.0 
)

Definition at line 271 of file ik.cpp.

int IK::assign_constraints ( int  _n)
protected

Definition at line 402 of file ik.cpp.

int IK::calc_feedback ( )
protected

Definition at line 112 of file update_ik.cpp.

int IK::calc_jacobian ( )
protected

compute the Jacobian matrix

Definition at line 66 of file update_ik.cpp.

int IK::ConstraintID ( ConstType  _type,
const char *  jname 
)

Obtaint the constraint ID by its type and joint name.

Returns
constraint ID

Definition at line 493 of file ik.cpp.

int IK::ConstraintID ( int  _index)

Obtaint the constraint ID by its index.

Returns
constraint ID

Definition at line 504 of file ik.cpp.

int IK::ConstraintIndex ( ConstType  _type,
const char *  jname 
)

Obtain the index of a constraint by its type and joint name.

Returns
index of the constraint

Definition at line 511 of file ik.cpp.

int IK::ConstraintIndex ( int  _id)

Obtain the index of a constraint by its type and ID.

Returns
index of the constraint

Definition at line 522 of file ik.cpp.

int IK::copy_jacobian ( )
protected

Definition at line 125 of file update_ik.cpp.

int IK::DisableDesire ( const char *  jname)

Disable desire constraint of the specific joint.

Definition at line 596 of file ik.cpp.

int IK::edit_marker ( IKHandle marker,
const char *  body_name,
Joint parent_joint,
const fVec3 abs_pos 
)
protected

Definition at line 306 of file ik.cpp.

int IK::EditMarker ( IKHandle marker,
const char *  body_name,
Joint parent_joint,
const fVec3 abs_pos = 0.0 
)

Definition at line 295 of file ik.cpp.

int IK::EnableDesire ( const char *  jname)

Enable desire constraint of the specific joint.

Definition at line 587 of file ik.cpp.

IKConstraint * IK::FindConstraint ( ConstType  _type,
const char *  jname,
const char *  charname = 0 
)

Search a constraint by constraint type and joint name.

Parameters
[in]_typeconstraint type
[in]jnamejoint name
[in]charnamecharacter name (optional)
Returns
pointer to the constraint

Definition at line 465 of file ik.cpp.

IKConstraint * IK::FindConstraint ( int  _id)

Search a constraint by the ID

Returns
pointer to the constraint

Definition at line 483 of file ik.cpp.

double IK::GetMaxConditionNumber ( )
inline

Get maximum condition number.

Definition at line 173 of file ik.h.

int IK::init ( SceneGraph *  sg)
protectedvirtual

Initialize the parameters.

Reimplemented from Chain.

Definition at line 54 of file ik.cpp.

int IK::load_markers ( SceneGraph *  sg,
Joint rj 
)
protected

Definition at line 89 of file ik.cpp.

int IK::load_markers ( TransformNode *  marker_top)
protected

Definition at line 110 of file ik.cpp.

int IK::LoadMarkerXML ( const char *  fname,
const char *  _charname 
)

Load marker information from XML file.

int IK::myinit ( SceneGraph *  sg)
protected

Definition at line 70 of file ik.cpp.

int IK::NumConstraints ( )
inline

Number of constraints.

Definition at line 77 of file ik.h.

int IK::NumConstraints ( ConstType  t)

Number of constraints with specific type.

Definition at line 392 of file ik.cpp.

int IK::RemoveAllConstraints ( )

Remove all constraints.

Definition at line 454 of file ik.cpp.

int IK::RemoveConstraint ( int  _id)

Remove a constraint.

Parameters
[in]_idID of the constraint to be removed
Returns
0 if success, -1 if failure (e.g. constraint not found)

Definition at line 439 of file ik.cpp.

int IK::ResetAllConstraints ( )

Reset all constraints.

Definition at line 532 of file ik.cpp.

int IK::ResetConstraints ( ConstType  t)

Reset the constraints with the specific type.

Definition at line 540 of file ik.cpp.

int IK::save_marker ( TransformNode *  top_tnode,
IKHandle h 
)
protected

Definition at line 357 of file ik.cpp.

int IK::SaveMarkers ( const char *  fname)

Definition at line 336 of file ik.cpp.

void IK::set_character_scale ( Joint jnt,
double  _scale,
const char *  charname 
)
protected

Definition at line 623 of file ik.cpp.

void IK::SetCharacterScale ( double  _scale,
const char *  charname = 0 
)

Set character scale parameter.

Definition at line 605 of file ik.cpp.

void IK::SetConstraintScale ( double  _scale,
const char *  charname = 0 
)

Set constraint scale parameter.

Definition at line 614 of file ik.cpp.

int IK::SetDesireGain ( const char *  jname,
double  _gain 
)

Set gain of desire constraint of the specific joint.

Definition at line 578 of file ik.cpp.

int IK::SetJointWeight ( const char *  jname,
double  _weight 
)

Set joint weight, for single-DOF joints.

Definition at line 551 of file ik.cpp.

int IK::SetJointWeight ( const char *  jname,
const fVec _weight 
)

Set joint weight, for multiple-DOF joints.

Definition at line 565 of file ik.cpp.

void IK::SetMaxConditionNumber ( double  cn)
inline

Set maximum condition number.

Definition at line 169 of file ik.h.

double IK::solve_ik ( )
protected

compute the joint velocity

Definition at line 157 of file update_ik.cpp.

double IK::Update ( double  timestep)

Perform inverse kinematics computation.

Parameters
[in]timestepintegration time step
Returns
the maximum condition number

Definition at line 24 of file update_ik.cpp.

double IK::Update ( double  max_timestep,
double  min_timestep,
double  max_integ_error = DEFAULT_MAX_INTEG_ERROR 
)

Perform inverse kinematics with adaptive time step.

Definition at line 46 of file update_ik.cpp.

Friends And Related Function Documentation

friend class IKConstraint
friend

Definition at line 40 of file ik.h.

friend class IKDesire
friend

Definition at line 42 of file ik.h.

friend class IKHandle
friend

Definition at line 41 of file ik.h.

Member Data Documentation

IKConstraint** IK::constraints
protected

list of current constraints

Definition at line 230 of file ik.h.

fVec IK::fb[N_PRIORITY_TYPES]
protected

constraint error of each type

Definition at line 236 of file ik.h.

fMat IK::J[N_PRIORITY_TYPES]
protected

Jacobian matrix of each type.

Definition at line 235 of file ik.h.

fVec IK::joint_weights
protected

joint weights

Definition at line 245 of file ik.h.

double IK::max_condnum
protected

maximum condition number

Definition at line 242 of file ik.h.

int IK::n_all_const
protected

Definition at line 239 of file ik.h.

int IK::n_assigned_constraints
protected

Definition at line 232 of file ik.h.

int IK::n_const[N_PRIORITY_TYPES]
protected

number of constraints of each type

Definition at line 238 of file ik.h.

int IK::n_constraints
protected

number of current constraints

Definition at line 224 of file ik.h.

int IK::n_total_const
protected

number of total constraints used so far, including removed ones

Definition at line 227 of file ik.h.

fVec IK::weight[N_PRIORITY_TYPES]
protected

weight of each type

Definition at line 237 of file ik.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 Apr 13 2019 02:14:28