Go to the source code of this file.
Classes | |
struct | TCurrentMot |
structure for the currently active axis More... | |
struct | TMovement |
structure for the More... | |
struct | TPos |
extern C because we want to access these interfaces from anywhere: More... | |
Macros | |
#define | DLLEXPORT |
Enumerations | |
enum | { ERR_NONE = 0, ERR_SUCCESS = 1 } |
enum | ETransition { PTP = 1, LINEAR = 2 } |
the transition types for a movement More... | |
Functions | |
DLLEXPORT int | allMotorsOff () |
DLLEXPORT int | allMotorsOn () |
DLLEXPORT int | calibrate (int axis) |
DLLEXPORT int | clearMoveBuffers () |
clears the movebuffers More... | |
DLLEXPORT int | closeGripper () |
DLLEXPORT int | deleteMovementFromStack (char *name, int index) |
DLLEXPORT int | deleteMovementStack (char *name) |
deletes a movemnt stack More... | |
DLLEXPORT int | executeConnectedMovement (struct TMovement *movement, struct TPos *startPos, bool first, bool last) |
DLLEXPORT int | executeMovement (struct TMovement *movement) |
DLLEXPORT int | flushMoveBuffers () |
flush all the movebuffers More... | |
DLLEXPORT int | getAxisFirmwareVersion (int axis, char value[]) |
gets the axis firmware version and returns it in the value argument More... | |
DLLEXPORT int | getCurrentControllerType (int axis) |
DLLEXPORT int | getDrive (int axis, int &value) |
DLLEXPORT int | getEncoder (int axis, int &value) |
DLLEXPORT int | getForce (int axis) |
set the current force More... | |
DLLEXPORT int | getNumberOfMotors () |
returns the number of motors configured More... | |
DLLEXPORT int | getPosition (struct TPos *pos) |
gets a position More... | |
DLLEXPORT int | getVelocity (int axis, int &value) |
DLLEXPORT int | getVersion (char value[]) |
gets the controlboard firmware version and returns it in the value argument More... | |
DLLEXPORT int | initKatana (char *configFile, char *ipaddress) |
This initializes the Katana (communication etc) More... | |
DLLEXPORT int | IO_readInput (int inputNr, int &value) |
DLLEXPORT int | IO_setOutput (char output, int value) |
DLLEXPORT int | ModBusTCP_readWord (int address, int &value) |
reads a value from the register 'address' (if not connected, connect to the IP in katana.conf) More... | |
DLLEXPORT int | ModBusTCP_writeWord (int address, int value) |
DLLEXPORT int | motorOff (int axis) |
DLLEXPORT int | motorOn (int axis) |
DLLEXPORT int | moveMot (int axis, int enc, int speed, int accel) |
DLLEXPORT int | moveMotAndWait (int axis, int targetpos, int tolerance) |
DLLEXPORT int | moveToPos (struct TPos *pos, int velocity, int acceleration) |
moves in IK More... | |
DLLEXPORT int | moveToPosEnc (int enc1, int enc2, int enc3, int enc4, int enc5, int enc6, int velocity, int acceleration, int tolerance, bool _wait) |
DLLEXPORT int | moveToPosLin (struct TPos *targetPos, int velocity, int acceleration) |
moves in LM More... | |
DLLEXPORT int | openGripper () |
DLLEXPORT int | ping (int axis) |
DLLEXPORT int | pushMovementToStack (struct TMovement *movement, char *name) |
DLLEXPORT int | runThroughMovementStack (char *name, int loops) |
DLLEXPORT int | sendSplineToMotor (int axis, int targetpos, int duration, int p0, int p1, int p2, int p3) |
DLLEXPORT int | setCollisionDetection (int axis, bool state) |
DLLEXPORT int | setCollisionParameters (int axis, int position, int velocity) |
DLLEXPORT int | setControllerParameters (int axis, int ki, int kspeed, int kpos) |
DLLEXPORT int | setForceLimit (int axis, int limit) |
DLLEXPORT int | setGripper (bool hasGripper) |
DLLEXPORT int | setMaxAccel (int axis, int acceleration) |
DLLEXPORT int | setMaxVelocity (int axis, int vel) |
DLLEXPORT int | setPositionCollisionLimit (int axis, int limit) |
DLLEXPORT int | setVelocityCollisionLimit (int axis, int limit) |
DLLEXPORT int | startSplineMovement (int contd, int exactflag) |
DLLEXPORT int | unblock () |
unblocks the robot after collision/instantstop More... | |
DLLEXPORT int | waitForMot (int axis, int targetpos, int tolerance) |
Variables | |
const double | PI = 3.14159265358979323846 |
#define DLLEXPORT |
Definition at line 30 of file kni_wrapper.h.
anonymous enum |
Enumerator | |
---|---|
ERR_NONE | |
ERR_SUCCESS |
Definition at line 36 of file kni_wrapper.h.
enum ETransition |
the transition types for a movement
Enumerator | |
---|---|
PTP |
Point-to-point movement. |
LINEAR |
linear movement |
Definition at line 56 of file kni_wrapper.h.
DLLEXPORT int allMotorsOff | ( | ) |
Switches all axes off
Definition at line 149 of file kni_wrapper.cpp.
DLLEXPORT int allMotorsOn | ( | ) |
Put all axes into hold state
Definition at line 163 of file kni_wrapper.cpp.
DLLEXPORT int calibrate | ( | int | axis | ) |
closes the Katana session
Definition at line 63 of file kni_wrapper.cpp.
DLLEXPORT int clearMoveBuffers | ( | ) |
clears the movebuffers
Definition at line 655 of file kni_wrapper.cpp.
DLLEXPORT int closeGripper | ( | ) |
closes the gripper if available
Definition at line 195 of file kni_wrapper.cpp.
DLLEXPORT int deleteMovementFromStack | ( | char * | name, |
int | index | ||
) |
deletes a movement from the stack
name | the name of the stack |
index | the index of the movement to delete |
Definition at line 359 of file kni_wrapper.cpp.
DLLEXPORT int deleteMovementStack | ( | char * | name | ) |
deletes a movemnt stack
Definition at line 396 of file kni_wrapper.cpp.
DLLEXPORT int executeConnectedMovement | ( | struct TMovement * | movement, |
struct TPos * | startPos, | ||
bool | first, | ||
bool | last | ||
) |
execute a connected movement
movement | a TMovement struct to execute |
startPos | a TPos struct with the start position, can be omitted if first=true |
first | if this is the first of the connected movements (start at current pos) |
last | if this is the last of the connected movements (wait for end of move) |
Definition at line 496 of file kni_wrapper.cpp.
execute a movement
movement | a TMovement struct to execute, starting from the current position |
Definition at line 482 of file kni_wrapper.cpp.
DLLEXPORT int flushMoveBuffers | ( | ) |
flush all the movebuffers
Definition at line 281 of file kni_wrapper.cpp.
DLLEXPORT int getAxisFirmwareVersion | ( | int | axis, |
char | value[] | ||
) |
gets the axis firmware version and returns it in the value argument
Definition at line 719 of file kni_wrapper.cpp.
DLLEXPORT int getCurrentControllerType | ( | int | axis | ) |
set the current controller limit
Definition at line 855 of file kni_wrapper.cpp.
DLLEXPORT int getDrive | ( | int | axis, |
int & | value | ||
) |
gets the pwm and returns it in the value argument
axis | The axis to send the command to |
Definition at line 688 of file kni_wrapper.cpp.
DLLEXPORT int getEncoder | ( | int | axis, |
int & | value | ||
) |
gets the position and returns it in the value argument
axis | The axis to send the command to |
Definition at line 704 of file kni_wrapper.cpp.
DLLEXPORT int getForce | ( | int | axis | ) |
set the current force
Definition at line 842 of file kni_wrapper.cpp.
DLLEXPORT int getNumberOfMotors | ( | ) |
returns the number of motors configured
Definition at line 940 of file kni_wrapper.cpp.
gets a position
Definition at line 295 of file kni_wrapper.cpp.
DLLEXPORT int getVelocity | ( | int | axis, |
int & | value | ||
) |
gets the velocity and returns it in the value argument
axis | The axis to send the command to |
Definition at line 672 of file kni_wrapper.cpp.
DLLEXPORT int getVersion | ( | char | value[] | ) |
gets the controlboard firmware version and returns it in the value argument
Definition at line 744 of file kni_wrapper.cpp.
DLLEXPORT int initKatana | ( | char * | configFile, |
char * | ipaddress | ||
) |
This initializes the Katana (communication etc)
Definition at line 39 of file kni_wrapper.cpp.
DLLEXPORT int IO_readInput | ( | int | inputNr, |
int & | value | ||
) |
reads an input from the digital I/O and returns it in the value argument
Definition at line 621 of file kni_wrapper.cpp.
DLLEXPORT int IO_setOutput | ( | char | output, |
int | value | ||
) |
sets an output of the digital I/Os
ouputNr | 1, or 2 for OutA or OutB |
Definition at line 596 of file kni_wrapper.cpp.
DLLEXPORT int ModBusTCP_readWord | ( | int | address, |
int & | value | ||
) |
reads a value from the register 'address' (if not connected, connect to the IP in katana.conf)
Definition at line 570 of file kni_wrapper.cpp.
DLLEXPORT int ModBusTCP_writeWord | ( | int | address, |
int | value | ||
) |
writes a value to the register 'address' (if not connected, connect to the IP in katana.conf)
Definition at line 546 of file kni_wrapper.cpp.
DLLEXPORT int motorOff | ( | int | axis | ) |
Switches an axis off
axis | The axis to send the command to |
Definition at line 135 of file kni_wrapper.cpp.
DLLEXPORT int motorOn | ( | int | axis | ) |
Switches an axis on
axis | The axis to send the command to |
Definition at line 121 of file kni_wrapper.cpp.
DLLEXPORT int moveMot | ( | int | axis, |
int | enc, | ||
int | speed, | ||
int | accel | ||
) |
PTP movement
axis | The axis to send the command to |
enc | the target position |
Definition at line 77 of file kni_wrapper.cpp.
DLLEXPORT int moveMotAndWait | ( | int | axis, |
int | targetpos, | ||
int | tolerance | ||
) |
calls MoveMot() and WaitForMot()
axis | The axis to send the command to |
tolerance | in encoder values (0 means wait until reached) |
Definition at line 106 of file kni_wrapper.cpp.
moves in IK
Definition at line 309 of file kni_wrapper.cpp.
DLLEXPORT int moveToPosEnc | ( | int | enc1, |
int | enc2, | ||
int | enc3, | ||
int | enc4, | ||
int | enc5, | ||
int | enc6, | ||
int | velocity, | ||
int | acceleration, | ||
int | tolerance, | ||
bool | _wait | ||
) |
Moves all axes to a target encoder value
enc | (encX) the target positions |
tolerance | in encoders. sent unscaled to axis and handled there. WaitForMot (and MoveMOtAndWait) checks the tolerance though. |
wait | wait for the movement to finish |
Definition at line 223 of file kni_wrapper.cpp.
moves in LM
Definition at line 325 of file kni_wrapper.cpp.
DLLEXPORT int openGripper | ( | ) |
opens the gripper if available
Definition at line 209 of file kni_wrapper.cpp.
DLLEXPORT int ping | ( | int | axis | ) |
checks the alive state of an axis
axis | 0 = get all axes |
Definition at line 954 of file kni_wrapper.cpp.
pushes a movement onto a stack
movement | a movement structure filled with position and movement parameters |
name | the name of the stack to push it onto |
Definition at line 341 of file kni_wrapper.cpp.
DLLEXPORT int runThroughMovementStack | ( | char * | name, |
int | loops | ||
) |
Runs through the movement stack, executes the movements
name | the name of the stack to run through |
loops | the number of loops to run |
Definition at line 426 of file kni_wrapper.cpp.
DLLEXPORT int sendSplineToMotor | ( | int | axis, |
int | targetpos, | ||
int | duration, | ||
int | p0, | ||
int | p1, | ||
int | p2, | ||
int | p3 | ||
) |
sends a single polynomial to an axis (G)
axis | The axis to send the command to |
Definition at line 252 of file kni_wrapper.cpp.
DLLEXPORT int setCollisionDetection | ( | int | axis, |
bool | state | ||
) |
sets the collision detection on the axes.
state | true = on |
axis | 0 = set all axes |
Definition at line 768 of file kni_wrapper.cpp.
DLLEXPORT int setCollisionParameters | ( | int | axis, |
int | position, | ||
int | velocity | ||
) |
sets the collision parameters this function internally calls setPositionCollisionLimit and setVelocityCollisionLimit
axis | 0 = set all axes |
position | range 1-10 |
velocity | range 1-10 |
Definition at line 813 of file kni_wrapper.cpp.
DLLEXPORT int setControllerParameters | ( | int | axis, |
int | ki, | ||
int | kspeed, | ||
int | kpos | ||
) |
sets the controller parameters
axis | 0 = set all axes |
Definition at line 882 of file kni_wrapper.cpp.
DLLEXPORT int setForceLimit | ( | int | axis, |
int | limit | ||
) |
set the force limit
axis | 0 = all axes |
limit | limit in percent |
Definition at line 828 of file kni_wrapper.cpp.
DLLEXPORT int setGripper | ( | bool | hasGripper | ) |
sets or unsets whether the Katana has a Gripper
hasGripper | set to true if a gripper is present. Default at startup: false |
Definition at line 177 of file kni_wrapper.cpp.
DLLEXPORT int setMaxAccel | ( | int | axis, |
int | acceleration | ||
) |
sets the maximum acceleration (allowed values are only 1 and 2)
axis | 0 = set all axes |
Definition at line 918 of file kni_wrapper.cpp.
DLLEXPORT int setMaxVelocity | ( | int | axis, |
int | vel | ||
) |
sets the maximum velocity
axis | 0 = set all axes |
vel | 1-180 are valid |
Definition at line 896 of file kni_wrapper.cpp.
DLLEXPORT int setPositionCollisionLimit | ( | int | axis, |
int | limit | ||
) |
set the position collision limit
axis | 0 = all axes |
Definition at line 785 of file kni_wrapper.cpp.
DLLEXPORT int setVelocityCollisionLimit | ( | int | axis, |
int | limit | ||
) |
set the velocity collision limit
axis | 0 = all axes |
Definition at line 799 of file kni_wrapper.cpp.
DLLEXPORT int startSplineMovement | ( | int | contd, |
int | exactflag | ||
) |
starts the linear movement (G+128)
Definition at line 266 of file kni_wrapper.cpp.
DLLEXPORT int unblock | ( | ) |
unblocks the robot after collision/instantstop
Definition at line 868 of file kni_wrapper.cpp.
DLLEXPORT int waitForMot | ( | int | axis, |
int | targetpos, | ||
int | tolerance | ||
) |
waits for a motor
axis | The axis to wait for |
targetpos | (only relevant if mode is 0) |
tolerance | (only relevant if mode is 0) in encoder values |
Definition at line 92 of file kni_wrapper.cpp.
const double PI = 3.14159265358979323846 |
Definition at line 34 of file kni_wrapper.h.