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) |
IKHandle * | AddMarker (const std::string &label, const std::string &linkname, const std::string &charname, const fVec3 &rel_pos) |
| Add new marker constraint.
|
IKHandle * | AddMarker (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.
|
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.
|
IKConstraint * | FindConstraint (ConstType _type, const char *jname, const char *charname=0) |
IKConstraint * | FindConstraint (int _id) |
double | GetMaxConditionNumber () |
| Get maximum condition number.
|
| IK () |
| Default constructor.
|
int | LoadMarkerXML (const char *fname, const char *_charname) |
| Load marker information from XML file.
|
int | NumConstraints () |
| Number of constraints.
|
int | NumConstraints (ConstType t) |
| Number of constraints with specific type.
|
int | RemoveAllConstraints () |
int | RemoveConstraint (int _id) |
int | ResetAllConstraints () |
| Reset all constraints.
|
int | ResetConstraints (ConstType t) |
| Reset the constraints with the specific type.
|
int | SaveMarkers (const char *fname) |
void | SetCharacterScale (double _scale, const char *charname=0) |
| Set character scale parameter.
|
void | SetConstraintScale (double _scale, const char *charname=0) |
| Set constraint scale parameter.
|
int | SetDesireGain (const char *jname, double _gain) |
| Set gain of desire constraint of the specific joint.
|
int | SetJointWeight (const char *jname, double _weight) |
| Set joint weight, for single-DOF joints.
|
int | SetJointWeight (const char *jname, const fVec &_weight) |
| Set joint weight, for multiple-DOF joints.
|
void | SetMaxConditionNumber (double cn) |
| Set maximum condition number.
|
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.
|
| ~IK () |
| Destructor.
|
Protected Member Functions |
IKHandle * | add_marker (const char *marker_name, Joint *parent_joint, const fVec3 &abs_pos) |
IKHandle * | add_marker (TransformNode *tn) |
int | assign_constraints (int _n) |
int | calc_feedback () |
int | calc_jacobian () |
| compute the Jacobian matrix
|
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.
|
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
|
Protected Attributes |
IKConstraint ** | constraints |
| list of current constraints
|
fVec | fb [N_PRIORITY_TYPES] |
| constraint error of each type
|
fMat | J [N_PRIORITY_TYPES] |
| Jacobian matrix of each type.
|
fVec | joint_weights |
| joint weights
|
double | max_condnum |
| maximum condition number
|
int | n_all_const |
int | n_assigned_constraints |
int | n_const [N_PRIORITY_TYPES] |
| number of constraints of each type
|
int | n_constraints |
| number of current constraints
|
int | n_total_const |
| number of total constraints used so far, including removed ones
|
fVec | weight [N_PRIORITY_TYPES] |
| weight of each type
|
Friends |
class | IKConstraint |
class | IKDesire |
class | IKHandle |
Main class for inverse kinematic computation.
Definition at line 37 of file ik.h.