|
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. More...
|
|
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. 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...
|
|
IKConstraint * | FindConstraint (ConstType _type, const char *jname, const char *charname=0) |
|
IKConstraint * | FindConstraint (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...
|
|
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...
|
|
Joint * | AddJoint (JointData *joint_data, const char *charname=0) |
| Create and add a joint using JointData structure. More...
|
|
Joint * | AddRoot (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...
|
|
Joint * | FindCharacterRoot (const char *charname) |
| Find the root joint of the character with name charname . More...
|
|
Joint * | FindJoint (const char *jname, const char *charname=0) |
| Find a joint from name. More...
|
|
Joint * | FindJoint (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 ×tep, 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...
|
|
Joint * | Root () |
|
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 () |
|
Main class for inverse kinematic computation.
Definition at line 37 of file ik.h.