$search
Go to the source code of this file.
Classes | |
struct | FloatVector |
struct | IntVector |
Defines | |
#define | _declspec(dllexport) int kin_setType(int type) |
This sets the robot type. | |
Typedefs | |
typedef struct FloatVector | FloatVector |
typedef struct IntVector | IntVector |
Variables | |
FloatVector FloatVector * | a |
FloatVector FloatVector FloatVector * | alpha |
FloatVector * | angle |
FloatVector * | angleK4D |
FloatVector * | angleMDH |
FloatVector * | d |
IntVector * | enc |
FloatVector FloatVector int | maxBisection = 0) |
const int | MaxDof = 10 |
Maximum degree of freedom. | |
FloatVector * | pose |
FloatVector * | prev |
FloatVector FloatVector FloatVector int | typeNr = -1) |
_declspec | ( | dllexport | ) |
This sets the robot type.
This calculates the inverse kinematics.
This calculates the direct kinematics.
This converts angles in mDH convention to encoders.
This converts encoders to angles in mDH convention.
This converts angles from mDH to Katana4D convention.
This converts angles from Katana4D to mDH convention.
This cleans the kinematics library.
This initializes the kinematic.
Get the version number of the library.
Get the tcp offset.
Get the angle range.
Get the angle offsets.
Get the rotation direction.
Get the encoder offsets.
Get the encoders per cycle.
Get the immobile flag of the last joint.
Get the modified Denavit-Hartenberg parameters.
Get the degree of mobility.
Get the degree of freedom.
Get the maximum degree of freedom.
Get the robot type.
This sets the tcp offset.
This sets the angle range.
This sets the angle offsets.
This sets the rotation direction.
This sets the encoder offsets.
This sets the encoders per cycle.
This sets the immobile flag of the last joint.
This sets the link length parameters (part of mDH-parameters).
This sets the modified Denavit-Hartenberg parameters.
Setting robot type includes setting mDH parameters, immobile flag, degree of freedom (dof), degree of mobility (dom) and angles.
type dof dom 6M90A_F 6 6 6M90A_G 6 5 6M180 5 5 6M90B_F 6 6 6M90B_G 6 5
type | 0: 6M90A_F, 1: 6M90A_G, 2: 6M180, 3: 6M90B_F, 4: 6M90B_G |
Transformation from previous to current link: move a along (previous) x-axis, rotate alpha about (previous) x-axis, move d along (current) z-axis, rotate theta about (current) z-axis. Setting the mDH parameters includes setting dof, adjusting immobile flag (all free) and dom (= dof).
The length of the vectors need to be the same.
theta | angle about z-axis | |
d | distance along x-axis | |
a | distance previous to current along previous x-axis | |
alpha | angle about previous x-axis | |
typeNr | 0: 6M90A_F, 1: 6M90A_G, 2: 6M180, 3: 6M90B_F, 4: 6M90B_G, -1: other |
Setting link length parameters requires the type to be set to 0 (6M90A_F), 1 (6M90A_G), 2 (6M180), 3 (6M90B_F) or 4 (6M90B_G). This is done using the setType or setModifiedDH function that set the mDH parameters so they can be adjusted. The length of the vector has to be four.
links | length of the links in m |
Flag for the last joint if it is free (0) or locked (1). Setting the immobile flag includes adjusting dom. Type or mDH parameters have to be set.
immobile | last joint immobile flag: 0 for free, 1 for locked (immobile) |
Number of encoders in a full cycle of each joint. Length of epc needs to be equal to DOM set with Type or mDH parameters.
epc | encoders pec cycle |
The encoder values at the calibration stops. Length of encOffset needs to be equal to DOM set with Type or mDH parameters.
encOffset | encoder values at calibration stops |
The rotation direction of the joints: +1 if encoders and angles (mDH convention) grow in same direction, -1 if encoders and angles grow in opposit direction. Length of rotDir needs to be equal to DOM set with Type or mDH parameters.
rotDir | rotation direction of the joints |
The angles at the calibration stops in mDH convention! Length of angleOffset needs to be equal to DOM set with Type or mDH parameters.
angleOffset | angle values at calibration stops in mDH |
The angle range from angle offset to angle stop in mDH convention (negative if angleOffset > angleStop)! Length of angleRange needs to be equal to DOM set with Type or mDH parameters.
angleRange | angle range from angle offset to angle stop |
Offset from the flange to the effective tcp.
tcpOffset | (x, y, z, psi) offset in m and rad respectively where psi is rotation about x-axis of tool coordinate system |
Get the robot type
Get the maximum degree of freedom (length of array in the vectors)
Get the degree of freedom
Get the degree of mobility
theta | vector to write in angle about z-axis | |
d | vector to write in distance along x-axis | |
a | vector to write in distance previous to current along previous x-axis | |
alpha | vector to write in angle about previous x-axis |
epc | vector to write in encoders pec cycle |
encOffset | vector to write in encoder values at calibration stops |
rotDir | vector to write in rotation direction of the joints |
angleOffset | vector to write in angle values at calibration stops in mDH |
angleRange | vector to write in angle range from angle offset to angle stop |
tcpOffset | vector to write in (x, y, z, psi) offset |
version | vector to write in version (major, minor, revision) |
Initialize the kinematic. Parameters mDH, dof, angle offset and angle range (SetType or SetMDH and SetAngleOffset and SetAngleRange) have to be set prior to initialization of the kinematic!
Free memory allocated in setType() / setMDH() before closing the library
Length of angleK4D needs to be equal to DOM set with Type or mDH parameters.
angleK4D | angle in K4D convention | |
angleMDH | angle in mDH convention |
Length of angleMDH needs to be equal to DOM set with Type or mDH parameters.
angleMDH | angle in mDH convention | |
angleK4D | angle in K4D convention |
Length of enc needs to be equal to DOM set with Type or mDH parameters.
enc | encoders | |
angle | angles in mDH convention |
Length of angle needs to be equal to DOM set with Type or mDH parameters.
angle | angle in mDH convention | |
enc | encoders |
Length of angle needs to be equal to DOM set with Type or mDH parameters.
angle | angles in mDH convention | |
pose | pose of the TCP [x, y, z, phi, theta, psi] |
Length of prev needs to be equal to DOM set with Type or mDH parameters.
pose | pose of the TCP [x, y, z, phi, theta, psi] | |
prev | previous angles (starting point) | |
angle | angles in mDH convention | |
maxBisection | maximum number of bisections done, if no solution found |
Definition at line 19 of file include/libKinematics.h.
typedef struct FloatVector FloatVector |
Definition at line 78 of file include/libKinematics.h.
Definition at line 78 of file include/libKinematics.h.
Definition at line 323 of file include/libKinematics.h.
Definition at line 313 of file include/libKinematics.h.
Definition at line 303 of file include/libKinematics.h.
FloatVector * d |
Definition at line 78 of file include/libKinematics.h.
Definition at line 333 of file include/libKinematics.h.
FloatVector FloatVector int maxBisection = 0) |
Definition at line 356 of file include/libKinematics.h.
const int MaxDof = 10 |
Maximum degree of freedom.
Definition at line 28 of file include/libKinematics.h.
Definition at line 343 of file include/libKinematics.h.
Definition at line 355 of file include/libKinematics.h.
FloatVector FloatVector FloatVector int typeNr = -1) |
Definition at line 79 of file include/libKinematics.h.