|
int | CalcJacobian (fMat &J) |
| The Jacobian matrix of position/orientation w.r.t. the joint values. More...
|
|
int | CalcJacobian2 (fMat *J2) |
| 2nd-order derivatives of the Jacobian matrix. More...
|
|
int | CalcJdot (fVec &jdot) |
| Jdot x thdot. More...
|
|
char * | CharName () const |
| Returns the character name. More...
|
|
int | DescendantDOF () |
| Total DOF of the descendants (end link side). More...
|
|
int | DescendantNumJoints () |
| Total number of joints of the descendants (end link side). More...
|
|
int | isAscendant (Joint *target) |
| Identifies whether the target joint is a direct ascendant. More...
|
|
int | isDescendant (Joint *target) |
| Identifies whether the target joint is a direct descendant. More...
|
|
| Joint () |
|
| Joint (const char *name, JointType jt=JUNKNOWN, const fVec3 &rpos=0.0, const fMat33 &ratt=1.0, AxisIndex _axis_index=AXIS_NULL, int t_given=true) |
|
| Joint (JointData *jdata, const char *charname) |
|
double | Scale () |
| Returns the scale applied to the joint. More...
|
|
void | SetFixedJointType (const fVec3 &rpos, const fMat33 &ratt) |
| Set joint type to fixed. More...
|
|
void | SetFreeJointType (const fVec3 &rpos, const fMat33 &ratt) |
| Set joint type to free. More...
|
|
void | SetJointData (JointData *jdata, const char *charname) |
|
int | SetJointOrientation (const fMat33 &r) |
| Set relative orientation. More...
|
|
int | SetJointPosition (const fVec3 &p) |
| Set relative position. More...
|
|
void | SetName (const char *_name, const char *_charname=0) |
| Change the joint name. More...
|
|
void | SetRotateJointType (const fVec3 &rpos, const fMat33 &ratt, AxisIndex ai) |
| Set joint type to rotational. More...
|
|
void | SetSlideJointType (const fVec3 &rpos, const fMat33 &ratt, AxisIndex ai) |
| Set joint type to prismatic. More...
|
|
void | SetSphereJointType (const fVec3 &rpos, const fMat33 &ratt) |
| Set joint type to spherical. More...
|
|
double | TotalMass () |
| Returns the total mass of the child links. More...
|
|
void | UpdateJointType () |
|
| ~Joint () |
|
|
Obtain/set the joint value/velocity/acceleration/force of a 1-DOF joint.
|
int | SetJointValue (double _q) |
|
int | SetJointVel (double _qd) |
|
int | SetJointAcc (double _qdd) |
|
int | GetJointValue (double &_q) |
|
int | GetJointVel (double &_qd) |
|
int | GetJointAcc (double &_qdd) |
|
int | SetJointForce (double _tau) |
|
int | GetJointForce (double &_tau) |
|
|
Obtain/set the joint value/velocity/acceleration/force of a 3-DOF joint.
|
int | SetJointValue (const fMat33 &r) |
|
int | SetJointValue (const fEulerPara &ep) |
|
int | SetJointVel (const fVec3 &rd) |
|
int | SetJointAcc (const fVec3 &rdd) |
|
int | SetJointAcc (double ax, double ay, double az) |
|
int | GetJointValue (fMat33 &r) |
|
int | GetJointVel (fVec3 &rd) |
|
int | GetJointAcc (fVec3 &rdd) |
|
int | SetJointForce (const fVec3 &_n3) |
|
int | GetJointForce (fVec3 &_n3) |
|
|
Obtain/set the joint value/velocity/acceleration/force of a 6-DOF joint.
|
int | SetJointValue (const fVec3 &p, const fMat33 &r) |
|
int | SetJointValue (const fVec3 &p, const fEulerPara &ep) |
|
int | SetJointVel (const fVec3 &pd, const fVec3 &rd) |
|
int | SetJointAcc (const fVec3 &pdd, const fVec3 &rdd) |
|
int | SetJointAcc (double lx, double ly, double lz, double ax, double ay, double az) |
|
int | GetJointValue (fVec3 &p, fMat33 &r) |
|
int | GetJointVel (fVec3 &pd, fVec3 &rd) |
|
int | GetJointAcc (fVec3 &pdd, fVec3 &rdd) |
|
int | SetJointForce (const fVec3 &_f3, const fVec3 &_n3) |
|
int | GetJointForce (fVec3 &_f3, fVec3 &_n3) |
|
|
void | _init_virtual () |
|
void | add_child (Joint *j) |
|
void | calc_acceleration () |
|
int | calc_jacobian (fMat &J, Joint *target) |
|
int | calc_jacobian_2 (fMat *J, Joint *target) |
|
int | calc_jacobian_2_free_sub (fMat *J, Joint *target, Joint *j1) |
|
int | calc_jacobian_2_rotate_rotate (fMat *J, Joint *target, Joint *j1, const fVec3 &axis1, int index1, const fVec3 &axis2, int index2) |
|
int | calc_jacobian_2_rotate_slide (fMat *J, Joint *target, Joint *jk, const fVec3 &k_axis, int k_index, const fVec3 &loc_axis, int loc_index) |
|
int | calc_jacobian_2_rotate_sub (fMat *J, Joint *target, Joint *j1) |
|
int | calc_jacobian_2_slide_rotate (fMat *J, Joint *target, Joint *jk, const fVec3 &k_axis, int k_index, const fVec3 &loc_axis, int loc_index) |
|
int | calc_jacobian_2_slide_sub (fMat *J, Joint *target, Joint *j1) |
|
int | calc_jacobian_2_sphere_sub (fMat *J, Joint *target, Joint *j1) |
|
int | calc_jacobian_free (fMat &J, Joint *target) |
|
int | calc_jacobian_rotate (fMat &J, Joint *target) |
|
int | calc_jacobian_slide (fMat &J, Joint *target) |
|
int | calc_jacobian_sphere (fMat &J, Joint *target) |
|
void | calc_joint_force (fVec &tau) |
|
void | calc_position () |
|
void | calc_velocity () |
|
void | clear () |
|
void | clear_data () |
|
int | clear_ext_force () |
|
int | clear_joint_force () |
|
double | com_jacobian (fMat &J, fVec3 &com, const char *chname) |
|
int | descendant_dof () |
|
int | descendant_num_joints () |
|
Joint * | find_joint (const char *n, const char *charname) |
|
Joint * | find_joint (int _id) |
|
int | get_joint_acc (fVec &accs) |
|
int | get_joint_force (fVec &forces) |
|
void | get_joint_list (Joint **joints) |
|
void | get_joint_name_list (char **jnames) |
|
int | get_joint_value (fVec &values) |
|
int | get_joint_vel (fVec &vels) |
|
void | init () |
|
void | init_arrays () |
|
void | init_virtual () |
|
void | inv_dyn () |
|
void | inv_dyn_1 () |
|
void | inv_dyn_2 () |
|
int | is_descendant (Joint *cur, Joint *target) |
|
int | post_integrate () |
|
int | pre_integrate () |
|
int | remove_child (Joint *j) |
|
int | save (ostream &ost, int indent, const char *charname) const |
|
int | save_xml (ostream &ost, int indent, const char *charname) const |
|
int | set_joint_acc (const fVec &accs) |
|
int | set_joint_force (const fVec &forces) |
|
int | set_joint_value (const fVec &values) |
|
int | set_joint_vel (const fVec &vels) |
|
double | total_com (fVec3 &com, const char *chname) |
|
double | total_mass () |
|
The class for representing a joint.
Definition at line 538 of file chain.h.