Tjoint Struct Reference

Detailed Description

Constraints on the relative moments between two links.

We store the pointers to the links related by the joint and also their identifiers. This is so because the identifiers are not stored in the links itselfs (they are the indexes of the links as stored in the mechanism).

Note that the .world syntax allow to define universal joints. However, we do not have a joint of type universal, since universal joints are two co-punctual revolute joints with orthogonal rotation axes. When we define a universal joint between link1 and link2, we add a ghost link between link1 and link2 with the X axis aligned with the first revolute joint of the universal joint (fixed w.r.t. link1) and the Y axis aligned with the second revolute joint of the universal joint (fixes w.r.t. link2). If we define ranges for the rotations of the universal joint, then the first range refers to the angle between the link1 and the ghost link defined from the joint and the second angle refers to the angle between the ghost link and link2.

Todo:
Right now only prismatic, spherical, revolute, universal and spherical-spherical joints are defined. Although it is not urgent, we have to define more types of joints: CYL_JOINT (cylindrical joint), and HEL_JOINT (helical joint).
To define a new type of joint, we have to define a new constructor, to to extend the GenerateJointEquations and the GenerateJointRangeEquations functions.
See Also
joint.h, joint.c.

Definition at line 168 of file joint.h.

Data Fields

unsigned int t
 
unsigned int id
 
unsigned int linkID [2]
 
Tlinklink [2]
 
double points [6][3]
 
double normals [3][3]
 
Tinterval normRange
 
boolean hasLimits
 
void * coupled
 
boolean avoidLimits
 
double avoidLimitsWeight
 
Tinterval range
 
Tinterval range2
 
double offset
 
double offset2
 
double vrange [2][3]
 
THTransform preT
 
THTransform postT
 
double maxCoord
 

Field Documentation

unsigned int Tjoint::id

Unique identifier assigned to the joint. This is used to generate unique names for the variables associated with the joint. Using the names of the links is informative but not enough since we can have several joint between the same couple of links.

Definition at line 172 of file joint.h.

Referenced by CopyJoint(), GenerateJointEquations(), GenerateJointEquationsInBranch(), GenerateJointRangeEquations(), GenerateJointRangeSingularityEquations(), GenerateJointSolution(), GetJointID(), GetJointTransSeq(), InitJoint(), RegenerateJointBox(), and RegenerateJointSolution().

unsigned int Tjoint::linkID[2]
double Tjoint::points[6][3]

In general, a joint constraints the relative motion between links stablishing relations between a vector defined in the first link reference frame and a vector defined in the second link reference frame.
In this case 4 points are used to define the two vectors (two points in the frame of reference of the first link and two points in that of the second link).
In some cases less than four points are necessary (for instance, for SPH_JOINTS only one point in each reference frame is required).
In other cases (for instance the IN_PATCH joint) 6 points are necessary: two to define the point and normal in the first link and 4 to define the patch in the second link.

Definition at line 180 of file joint.h.

Referenced by CopyJoint(), GenerateJointEquations(), GenerateJointEquationsInBranch(), GetJointDOFValues(), GetJointPoint(), GetJointTransform(), GetJointTransSeq(), InitJoint(), NewFixJoint(), NewInPatchJoint(), NewPrismaticJoint(), NewRevoluteJoint(), NewSphericalJoint(), NewUniversalJoint(), PrintJoint(), and PrintJointAxes().

double Tjoint::normals[3][3]

In general, normalized version of the two vectors defined from the points. In this case only 2 vectors are defined.
For the IN_PATCH_JOINT, normals at the corners of the patch used to compute the normal at any point in the patch. In this case tree vectors are defined

Definition at line 194 of file joint.h.

Referenced by CopyJoint(), GenerateJointEquations(), GenerateJointEquationsInBranch(), GenerateJointSolution(), GetJointDOFValues(), GetJointTransform(), GetJointTransSeq(), InitJoint(), NewInPatchJoint(), NewPrismaticJoint(), NewRevoluteJoint(), NewUniversalJoint(), and PrintJointAxes().

Tinterval Tjoint::normRange

For IN_PATCH_JOINT the range for the norm of the normal vector to any point in the patch. Not used for other joints.

Definition at line 200 of file joint.h.

Referenced by CopyJoint(), GenerateJointEquations(), InitJoint(), and NewInPatchJoint().

void* Tjoint::coupled

Pointer for the joint coupled with this one. This is only not NULL for some revolute joints coupled with the previous joint (revolute too and both joints with limits).

Definition at line 204 of file joint.h.

Referenced by CopyJoint(), CoupledWith(), GenerateJointRangeEquations(), GetJointDOF(), GetJointDOFValues(), GetJointTransSeq(), InitJoint(), and NewRevoluteJoint().

boolean Tjoint::avoidLimits

TRUE if the search process has to be focussed in the center of the valid ranges for the joint

Definition at line 208 of file joint.h.

Referenced by CopyJoint(), GenerateJointRangeEquations(), InitJoint(), NewInPatchJoint(), NewPrismaticJoint(), NewRevoluteJoint(), NewSphericalJoint(), NewUniversalJoint(), and PrintJoint().

double Tjoint::avoidLimitsWeight

If avoidLimits is TRUE, this is the strength of the limit avoidance for this joint.

Definition at line 210 of file joint.h.

Referenced by CopyJoint(), GenerateJointRangeEquations(), InitJoint(), NewInPatchJoint(), NewPrismaticJoint(), NewRevoluteJoint(), NewSphericalJoint(), and NewUniversalJoint().

Tinterval Tjoint::range2

For universal joints a second range is used (only if hasLimits is TRUE).

Definition at line 213 of file joint.h.

Referenced by CopyJoint(), DeleteJoint(), GenerateJointRangeEquations(), GenerateJointRangeSingularityEquations(), GetJointRangeN(), GetJointSecondRange(), InitJoint(), NewInPatchJoint(), NewUniversalJoint(), and PrintJoint().

double Tjoint::offset

Offset for range. Ranges are sometimes zero centered. We store the offset applied to zero-center the ranges to be able to recover the original ranges when necessary.

Definition at line 215 of file joint.h.

Referenced by CopyJoint(), GetJointRangeN(), InitJoint(), NewRevoluteJoint(), NewSphericalJoint(), and NewUniversalJoint().

double Tjoint::offset2

Offset for range2.

Definition at line 218 of file joint.h.

Referenced by CopyJoint(), GetJointRangeN(), InitJoint(), and NewUniversalJoint().

double Tjoint::vrange[2][3]

Vectors defining the reference position for rotations, spherical, and universal joints.

Definition at line 219 of file joint.h.

Referenced by CopyJoint(), GenerateJointRangeEquations(), GenerateJointSolution(), NewRevoluteJoint(), NewSphericalJoint(), NewUniversalJoint(), and PrintJoint().

THTransform Tjoint::preT

Transform used to obtain the reference frame of the second link involved in the joint from the first one. In particular this matrix accumulates the constant transforms to be applied before the applying the joint degrees of freedom.

Definition at line 222 of file joint.h.

Referenced by CopyJoint(), DeleteJoint(), GenerateJointEquations(), GetJointDOFValues(), GetJointTransform(), GetJointTransSeq(), InitJoint(), NewFixJoint(), NewInPatchJoint(), NewPrismaticJoint(), NewRevLowJoint(), NewRevoluteJoint(), NewRevUpJoint(), NewSphericalJoint(), NewSphSphUpJoint(), NewUniversalJoint(), and PrintJoint().

THTransform Tjoint::postT

Transform used to obtain the reference frame of the second link involved in the joint from the first one. In particular this matrix accumulates the constant transforms to be applied after the applying the joint degrees of freedom.

Definition at line 226 of file joint.h.

Referenced by CopyJoint(), DeleteJoint(), GetJointDOFValues(), GetJointTransform(), GetJointTransSeq(), InitJoint(), NewInPatchJoint(), NewPrismaticJoint(), NewRevLowJoint(), NewRevoluteJoint(), NewRevUpJoint(), NewSphericalJoint(), and NewUniversalJoint().

double Tjoint::maxCoord