Classes | Macros | Typedefs | Variables
lib/kinematics/libKinematics.h File Reference
#include <stdio.h>
#include <vector>
#include <iostream>
#include <string>
#include <cmath>
#include <fstream>
#include <ctime>
#include "kinematics.h"
Include dependency graph for lib/kinematics/libKinematics.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  FloatVector
 
struct  IntVector
 

Macros

#define _declspec(dllexport) int kin_setType(int type)
 This sets the robot type. More...
 

Typedefs

typedef struct FloatVector FloatVector
 
typedef struct IntVector IntVector
 

Variables

FloatVector FloatVectora
 
FloatVector FloatVector FloatVectoralpha
 
FloatVectorangle
 
FloatVectorangleK4D
 
FloatVectorangleMDH
 
FloatVectord
 
IntVectorenc
 
FloatVector FloatVector int maxBisection = 0)
 
FloatVectorpose
 
FloatVectorprev
 
FloatVector FloatVector FloatVector int typeNr = -1)
 

Macro Definition Documentation

#define _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

Parameters
type0: 6M90A_F, 1: 6M90A_G, 2: 6M180, 3: 6M90B_F, 4: 6M90B_G
Returns
0 if successful, < 0 if failed

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.

Parameters
thetaangle about z-axis
ddistance along x-axis
adistance previous to current along previous x-axis
alphaangle about previous x-axis
typeNr0: 6M90A_F, 1: 6M90A_G, 2: 6M180, 3: 6M90B_F, 4: 6M90B_G, -1: other
Returns
0 if successful, < 0 if failed

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.

Parameters
linkslength of the links in m
Returns
0 if successful, < 0 if failed

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.

Parameters
immobilelast joint immobile flag: 0 for free, 1 for locked (immobile)
Returns
0 if successful, < 0 if failed

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.

Parameters
epcencoders pec cycle
Returns
0 if successful, < 0 if failed

The encoder values at the calibration stops. Length of encOffset needs to be equal to DOM set with Type or mDH parameters.

Parameters
encOffsetencoder values at calibration stops
Returns
0 if successful, < 0 if failed

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.

Parameters
rotDirrotation direction of the joints
Returns
0 if successful, < 0 if failed

The angles at the calibration stops in mDH convention! Length of angleOffset needs to be equal to DOM set with Type or mDH parameters.

Parameters
angleOffsetangle values at calibration stops in mDH
Returns
0 if successful, < 0 if failed

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.

Parameters
angleRangeangle range from angle offset to angle stop
Returns
0 if successful, < 0 if failed

Offset from the flange to the effective tcp.

Parameters
tcpOffset(x, y, z, psi) offset in m and rad respectively where psi is rotation about x-axis of tool coordinate system
Returns
0 if successful, < 0 if failed

Get the robot type

Returns
0 for 6M90A_F, 1 for 6M90A_G, 2 for 6M180, 3 for 6M90B_F, 4 for 6M90B_G, -1 for other or not set yet

Get the maximum degree of freedom (length of array in the vectors)

Returns
Maximum degree of freedom

Get the degree of freedom

Returns
Degree of freedom or -1 if not set yet

Get the degree of mobility

Returns
Degree of mobility or -1 if not set yet
Parameters
thetavector to write in angle about z-axis
dvector to write in distance along x-axis
avector to write in distance previous to current along previous x-axis
alphavector to write in angle about previous x-axis
Returns
0 if successful, < 0 if failed
0 if mobile, 1 if immobile, < 0 if failed
Parameters
epcvector to write in encoders pec cycle
Returns
0 if successful, < 0 if failed
Parameters
encOffsetvector to write in encoder values at calibration stops
Returns
0 if successful, < 0 if failed
Parameters
rotDirvector to write in rotation direction of the joints
Returns
0 if successful, < 0 if failed
Parameters
angleOffsetvector to write in angle values at calibration stops in mDH
Returns
0 if successful, < 0 if failed
Parameters
angleRangevector to write in angle range from angle offset to angle stop
Returns
0 if successful, < 0 if failed
Parameters
tcpOffsetvector to write in (x, y, z, psi) offset
Returns
0 if successful, < 0 if failed
Parameters
versionvector to write in version (major, minor, revision)
Returns
0 if successful, < 0 if failed

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!

Returns
0 if successful, < 0 if failed

Free memory allocated in setType() / setMDH() before closing the library

Returns
0 if successful, < 0 if failed

Length of angleK4D needs to be equal to DOM set with Type or mDH parameters.

Parameters
angleK4Dangle in K4D convention
angleMDHangle in mDH convention
Returns
0 if successful, < 0 if failed

Length of angleMDH needs to be equal to DOM set with Type or mDH parameters.

Parameters
angleMDHangle in mDH convention
angleK4Dangle in K4D convention
Returns
0 if successful, < 0 if failed

Length of enc needs to be equal to DOM set with Type or mDH parameters.

Parameters
encencoders
angleangles in mDH convention
Returns
0 if successful, < 0 if failed

Length of angle needs to be equal to DOM set with Type or mDH parameters.

Parameters
angleangle in mDH convention
encencoders
Returns
0 if successful, < 0 if failed

Length of angle needs to be equal to DOM set with Type or mDH parameters.

Parameters
angleangles in mDH convention
posepose of the TCP [x, y, z, phi, theta, psi]
Returns
0 if successful, < 0 if failed

Length of prev needs to be equal to DOM set with Type or mDH parameters.

Parameters
posepose of the TCP [x, y, z, phi, theta, psi]
prevprevious angles (starting point)
angleangles in mDH convention
maxBisectionmaximum number of bisections done, if no solution found
Returns
0 if successful, < 0 if failed

Definition at line 19 of file lib/kinematics/libKinematics.h.

Typedef Documentation

typedef struct FloatVector FloatVector
typedef struct IntVector IntVector

Variable Documentation

Definition at line 88 of file lib/kinematics/libKinematics.h.

Definition at line 88 of file lib/kinematics/libKinematics.h.

Definition at line 333 of file lib/kinematics/libKinematics.h.

FloatVector* angleK4D

Definition at line 323 of file lib/kinematics/libKinematics.h.

FloatVector* angleMDH

Definition at line 313 of file lib/kinematics/libKinematics.h.

Definition at line 88 of file lib/kinematics/libKinematics.h.

IntVector* enc

Definition at line 343 of file lib/kinematics/libKinematics.h.

FloatVector FloatVector int maxBisection = 0)

Definition at line 366 of file lib/kinematics/libKinematics.h.

FloatVector* pose

Definition at line 353 of file lib/kinematics/libKinematics.h.

FloatVector* prev

Definition at line 365 of file lib/kinematics/libKinematics.h.

Definition at line 89 of file lib/kinematics/libKinematics.h.



kni
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:45