joint.h
Go to the documentation of this file.
1 #ifndef JOINTH
2 #define JOINTH
3 
4 #include "interval.h"
5 #include "link.h"
6 #include "boolean.h"
7 #include "cuiksystem.h"
8 #include "color.h"
9 #include "htransform.h"
10 #include "eqvector.h"
11 
12 #include <stdlib.h>
13 
14 
24 /************************************************************************************/
31 #define NO_JOINT NO_UINT
32 
40 #define FREE_JOINT 0
41 
51 #define FIX_JOINT 1
52 
59 #define REV_JOINT 2
60 
67 #define UNV_JOINT 3
68 
75 #define SPH_JOINT 4
76 
84 #define SPH_SPH_LOW_JOINT 5
85 
93 #define SPH_SPH_UP_JOINT 6
94 
101 #define REV_LOW_JOINT 7
102 
109 #define REV_UP_JOINT 8
110 
117 #define PRS_JOINT 9
118 
132 #define IN_PATCH_JOINT 10
133 
134 
135 /************************************************************************************/
136 
168 typedef struct {
169  unsigned int t;
172  unsigned int id;
177  unsigned int linkID[2];
178  Tlink *link[2];
180  double points[6][3];
194  double normals[3][3];
203  boolean hasLimits;
204  void *coupled;
208  boolean avoidLimits;
215  double offset;
218  double offset2;
219  double vrange[2][3];
230  double maxCoord;
231 } Tjoint;
232 
253 void NewFreeJoint(unsigned int id,
254  unsigned int linkID1,Tlink *link1,
255  unsigned int linkID2,Tlink *link2,
256  Tjoint *j);
257 
275 void NewFixJoint(unsigned int id,
276  unsigned int linkID1,Tlink *link1,
277  unsigned int linkID2,Tlink *link2,
278  THTransform *t,
279  Tjoint *j);
324 void NewRevoluteJoint(unsigned int id,unsigned int r,
325  unsigned int linkID1,Tlink *link1,
326  unsigned int linkID2,Tlink *link2,
327  double **points,
328  boolean hasLimits,Tinterval *range,double **rPoints,
329  boolean avoidLimits,double avoidLimitsWeight,
330  Tjoint *coupled,
331  Tjoint *j);
366 void NewUniversalJoint(unsigned int id,unsigned int r,
367  unsigned int linkID1,Tlink *link1,
368  unsigned int linkID2,Tlink *link2,
369  double **points,
370  boolean hasLimits,Tinterval *range1,Tinterval *range2,double **rPoints,
371  boolean avoidLimits,double avoidLimitsWeight,
372  Tjoint *j);
373 
407 void NewSphericalJoint(unsigned int id,
408  unsigned int linkID1,Tlink *link1,
409  unsigned int linkID2,Tlink *link2,
410  double **points,
411  boolean hasLimits,double range,double **rPoints,
412  boolean avoidLimits,double avoidLimitsWeight,
413  Tjoint *j);
414 
443 void NewPrismaticJoint(unsigned int id,
444  unsigned int linkID1,Tlink *link1,
445  unsigned int linkID2,Tlink *link2,
446  double **points,
447  Tinterval *range,
448  boolean avoidLimits,double avoidLimitsWeight,
449  Tjoint *j);
475 void NewSphSphLowJoint(unsigned int id,
476  unsigned int linkID1,Tlink *link1,
477  unsigned int linkID2,Tlink *link2,
478  double **points,
479  Tjoint *j);
496 void NewSphSphUpJoint(unsigned int id,
497  unsigned int linkID1,Tlink *link1,
498  unsigned int linkID2,Tlink *link2,
499  double **points,
500  Tjoint *j);
501 
521 void NewRevLowJoint(unsigned int id,
522  unsigned int linkID1,Tlink *link1,
523  unsigned int linkID2,Tlink *link2,
524  double **points,
525  Tjoint *j);
526 
546 void NewRevUpJoint(unsigned int id,
547  unsigned int linkID1,Tlink *link1,
548  unsigned int linkID2,Tlink *link2,
549  double **points,
550  Tjoint *j);
551 
576 void NewSphPrsSphLowJoint(unsigned int id,
577  unsigned int linkID1,Tlink *link1,
578  unsigned int linkID2,Tlink *link2,
579  double **points,
580  Tjoint *j);
581 
597 void NewSphPrsSphUpJoint(unsigned int id,
598  unsigned int linkID1,Tlink *link1,
599  unsigned int linkID2,Tlink *link2,
600  double **points,
601  Tjoint *j);
602 
632 void NewInPatchJoint(unsigned int id,
633  unsigned int linkID1,Tlink *link1,
634  unsigned int linkID2,Tlink *link2,
635  double **points,
636  double **patch,
637  boolean avoidLimits,double avoidLimitsWeight,
638  Tjoint *j);
639 
648 void CopyJoint(Tjoint *j_dst,Tjoint *j_src);
649 
659 unsigned int GetJointType(Tjoint *j);
660 
671 double GetJointMaxCoordinate(Tjoint *j);
672 
673 
683 unsigned int GetJointID(Tjoint *j);
684 
694 unsigned int JointFromID(Tjoint *j);
695 
705 Tlink *JointFrom(Tjoint *j);
706 
716 unsigned int JointToID(Tjoint *j);
717 
718 
728 Tlink *JointTo(Tjoint *j);
729 
741 void GetJointName(char **name,Tjoint *j);
742 
757 void GetJointDOFName(unsigned int ndof,char **name,Tjoint *j);
758 
773 void GetJointPoint(unsigned int link,unsigned int point,double *p,Tjoint *j);
774 
775 
785 boolean LimitedJoint(Tjoint *j);
786 
787 
799 
813 
814 
825 void GetJointRangeN(unsigned int nr,double mt,Tinterval *r,Tjoint *j);
826 
837 unsigned int GetJointRangeTopology(unsigned int nr,Tjoint *j);
838 
859 unsigned int CoupledWith(Tjoint *j);
860 
872 unsigned int GetJointDOF(Tjoint *j);
873 
887 
905 
906 
931  Tequation *eq,Tjoint *j);
932 
950 void JointForceEquation(Tparameters *pr,unsigned int linkID,TCuikSystem *cs,
951  Tequation *eq,Tjoint *j);
952 
966 void GenerateJointEquations(Tparameters *p,double maxCoord,
967  TCuikSystem *cs,Tjoint *j);
968 
990 void RegenerateJointSolution(Tparameters *p,TCuikSystem *cs,double *sol,Tjoint *j);
991 
1009 
1037 void GenerateJointSolution(Tparameters *p,double *dof,
1038  THTransform *t1,THTransform *t2,
1039  TCuikSystem *cs,double *sol,Tjoint *j);
1040 
1041 
1055 void GetJointTransform(double *dof,THTransform *t,Tjoint *j);
1056 
1083 void GetJointDOFValues(Tparameters *p,THTransform *t1,THTransform *t2,double *dof,
1084  Tjoint *j);
1085 
1086 
1099 
1100 
1118 void PrintJointAxes(Tparameters *p,FILE *f,TCuikSystem *cs,double *sol,
1119  double *r,Tjoint *j);
1120 
1130 void PrintJoint(FILE *f,Tjoint *j);
1131 
1139 void DeleteJoint(Tjoint *j);
1140 
1141 #endif
Definition of the boolean type.
void GetJointDOFName(unsigned int ndof, char **name, Tjoint *j)
Label for a specific dof of a joint.
Definition: joint.c:1006
void GetJointTransform(double *dof, THTransform *t, Tjoint *j)
Computes the transform induced by the joint.
Definition: joint.c:2537
void RegenerateJointSolution(Tparameters *p, TCuikSystem *cs, double *sol, Tjoint *j)
Computes the values for the dummy variables used in the joint equations.
Definition: joint.c:2291
void GetJointPoint(unsigned int link, unsigned int point, double *p, Tjoint *j)
Gets one of the points defining the rotation/sliding axis for the joint.
Definition: joint.c:1102
double GetJointMaxCoordinate(Tjoint *j)
Gets the maximum coordinate.
Definition: joint.c:936
void GetJointDOFValues(Tparameters *p, THTransform *t1, THTransform *t2, double *dof, Tjoint *j)
Recovers the joint DOFs from the absolute poses of the links.
Definition: joint.c:2638
double maxCoord
Definition: joint.h:230
Relation between two links.
Definition: joint.h:168
unsigned int GetJointDOF(Tjoint *j)
Computes the degrees of freedom allowed by a given joint.
Definition: joint.c:1293
boolean avoidLimits
Definition: joint.h:208
A homgeneous transform in R^3.
boolean hasLimits
Definition: joint.h:203
Tinterval * GetJointSecondRange(Tjoint *j)
Checks the second limit of a universal joint.
Definition: joint.c:1122
Tlink * JointFrom(Tjoint *j)
Gets a pointer to the first link involved in the joint.
Definition: joint.c:951
unsigned int CoupledWith(Tjoint *j)
Returns the identifier of the joint coupled with the query joint.
Definition: joint.c:1285
double offset2
Definition: joint.h:218
Definition of the TEqVEctor type and the associated functions.
void NewRevUpJoint(unsigned int id, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, double **points, Tjoint *j)
Constructor.
Definition: joint.c:668
void GenerateJointEquationsInBranch(Tparameters *p, double s, TCuikSystem *cs, Tequation *eq, Tjoint *j)
Generate the constraints of a joint in a sequence.
Definition: joint.c:1812
void GetJointName(char **name, Tjoint *j)
Returns a string identifying the joint.
Definition: joint.c:966
Tlink * JointTo(Tjoint *j)
Gets a pointer to the second link involved in the joint.
Definition: joint.c:961
unsigned int GetJointID(Tjoint *j)
Gets the joint identifier.
Definition: joint.c:941
Tinterval range
Definition: joint.h:212
void NewFreeJoint(unsigned int id, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, Tjoint *j)
Constructor.
Definition: joint.c:93
unsigned int id
Definition: joint.h:172
An equation.
Definition: equation.h:237
void * coupled
Definition: joint.h:204
void NewSphSphLowJoint(unsigned int id, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, double **points, Tjoint *j)
Constructor.
Definition: joint.c:601
THTransform postT
Definition: joint.h:226
unsigned int GetJointRangeTopology(unsigned int nr, Tjoint *j)
Returns the topology of one of the ranges of the joint.
Definition: joint.c:1214
void NewRevoluteJoint(unsigned int id, unsigned int r, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, double **points, boolean hasLimits, Tinterval *range, double **rPoints, boolean avoidLimits, double avoidLimitsWeight, Tjoint *coupled, Tjoint *j)
Constructor.
Definition: joint.c:124
void NewUniversalJoint(unsigned int id, unsigned int r, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, double **points, boolean hasLimits, Tinterval *range1, Tinterval *range2, double **rPoints, boolean avoidLimits, double avoidLimitsWeight, Tjoint *j)
Constructor.
Definition: joint.c:280
void PrintJointAxes(Tparameters *p, FILE *f, TCuikSystem *cs, double *sol, double *r, Tjoint *j)
Prints the joint axis in world coordinates.
Definition: joint.c:3014
void NewInPatchJoint(unsigned int id, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, double **points, double **patch, boolean avoidLimits, double avoidLimitsWeight, Tjoint *j)
Constructor.
Definition: joint.c:715
boolean LimitedJoint(Tjoint *j)
Checks if a joint has limits.
Definition: joint.c:1112
unsigned int GetJointType(Tjoint *j)
Gets the joint type.
Definition: joint.c:931
A table of parameters.
Definition of the TCuikSystem type and the associated functions.
THTransform preT
Definition: joint.h:222
Definition of the THTransform type and the associated functions.
A sequence of transforms.
Definition: trans_seq.h:319
void NewFixJoint(unsigned int id, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, THTransform *t, Tjoint *j)
Constructor.
Definition: joint.c:102
void GetJointTransSeq(Tparameters *p, TCuikSystem *cs, TTransSeq *ts, Tjoint *j)
Build the sequence of transforms passing through the joint.
Definition: joint.c:2829
A box.
Definition: box.h:83
void PrintJoint(FILE *f, Tjoint *j)
Stores the joint information into a file.
Definition: joint.c:3054
A cuiksystem, i.e., a set of variables and equations defining a position analysis problem...
Definition: cuiksystem.h:181
Definition of the Tcolor type and the associated functions.
Tinterval normRange
Definition: joint.h:200
unsigned int JointFromID(Tjoint *j)
Gets the identifier of the first link involved in the joint.
Definition: joint.c:946
void JointForceEquation(Tparameters *pr, unsigned int linkID, TCuikSystem *cs, Tequation *eq, Tjoint *j)
Add the force terms derived from a given joint.
Definition: joint.c:1925
void NewSphPrsSphUpJoint(unsigned int id, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, double **points, Tjoint *j)
Constructor.
void GenerateJointSolution(Tparameters *p, double *dof, THTransform *t1, THTransform *t2, TCuikSystem *cs, double *sol, Tjoint *j)
Generates a solution point from degrees of freedom.
Definition: joint.c:2365
void NewRevLowJoint(unsigned int id, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, double **points, Tjoint *j)
Constructor.
Definition: joint.c:627
void NewSphericalJoint(unsigned int id, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, double **points, boolean hasLimits, double range, double **rPoints, boolean avoidLimits, double avoidLimitsWeight, Tjoint *j)
Constructor.
Definition: joint.c:444
double avoidLimitsWeight
Definition: joint.h:210
unsigned int t
Definition: joint.h:169
double offset
Definition: joint.h:215
void GenerateJointRangeSingularityEquations(Tparameters *p, TCuikSystem *cs, Tjoint *j)
Modifies the cuik system to detect end range singularities.
Definition: joint.c:1333
Tinterval range2
Definition: joint.h:213
Defines a interval.
Definition: interval.h:33
Tinterval * GetJointRange(Tjoint *j)
Checks the limits of a joint.
Definition: joint.c:1117
void DeleteJoint(Tjoint *j)
Destructor.
Definition: joint.c:3190
void GenerateJointRangeEquations(Tparameters *p, TCuikSystem *cs, Tjoint *j)
Generate the constraints related with the joint limits.
Definition: joint.c:1521
void CopyJoint(Tjoint *j_dst, Tjoint *j_src)
Copy constructor.
Definition: joint.c:879
void GenerateJointEquations(Tparameters *p, double maxCoord, TCuikSystem *cs, Tjoint *j)
Generate the constraints related with the joint.
Definition: joint.c:1967
void NewSphSphUpJoint(unsigned int id, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, double **points, Tjoint *j)
Constructor.
Definition: joint.c:612
void GetJointRangeN(unsigned int nr, double mt, Tinterval *r, Tjoint *j)
Returns one of the ranges of the joint.
Definition: joint.c:1127
void NewPrismaticJoint(unsigned int id, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, double **points, Tinterval *range, boolean avoidLimits, double avoidLimitsWeight, Tjoint *j)
Constructor.
Definition: joint.c:533
unsigned int JointToID(Tjoint *j)
Gets the identifier of the second link involved in the joint.
Definition: joint.c:956
Definition of the Tinterval type and the associated functions.
void RegenerateJointBox(Tparameters *p, TCuikSystem *cs, Tbox *b, Tjoint *j)
Computes the values for the dummy variables used in the joint equations.
Definition: joint.c:2327
void NewSphPrsSphLowJoint(unsigned int id, unsigned int linkID1, Tlink *link1, unsigned int linkID2, Tlink *link2, double **points, Tjoint *j)
Constructor.