EASY-ROB™ Kernel
v8.606
|
Method class to create, attach, update devices, for kinematics calculations and for motion planning and -execution. More...
#include <erk_capi.h>
Static Public Member Functions | |
static DLLAPI int ER_STDCALL | erInitKin (ER_HND *er_hnd, Host_HND host_hnd=NULL) |
Create a unique kinematics handle. Opcode 101, Chapter 3.4.1, Page 3-26, same as erINITIALIZE() Initializes one instance of a robot and creates an unique kinematics handle er_hnd belonging to a robot kinematics.This handles is necessary to access individual data from the robot and to call other functions. Use erLoadKin() to load an EASY-ROB rob file (*.rob) containing a kinematics. More... | |
static DLLAPI int ER_STDCALL | erUnloadKin (ER_HND *er_hnd) |
Unload an instance of kinematics of the Kernel. Unloads an instance of kinematics givin by the unique kinematics handle. Unloading a kinematics will call callback function TerFreeGeometryProc for each geometry belonging to this kinematics. The number of loaded kinematics will be decremented. This kinematics handle er_hnd is set to NULL and is not valid after calling this function. More... | |
static DLLAPI int ER_STDCALL | erConnectPositioner (ER_HND er_hnd, ER_HND er_hnd_connect) |
Connects a positioner kinematics with handle er_hnd_connect to the robot kinematics with handle er_hnd .Remarks Use erConnectPositionerSetSync() for synchronized motion with a positioner. Use erConnectPositionerGetSync() to receive synchronization status between robot and the connected positioner. More... | |
static DLLAPI ER_HND ER_STDCALL | erConnectPositionerGetHND (ER_HND er_hnd) |
Get robots connection handle between robot and positioner. See also erConnectPositioner() More... | |
static DLLAPI int ER_STDCALL | erConnectPositionerSetSync (ER_HND er_hnd, long connect_sync) |
Set robots synchronization flag for synchronization between robot and positioner. The synchronization flag connect_sync can be one of the following values.1: ER_SYNC_OFF, 2: ER_SYNC_ON See also erConnectPositionerGetSync() More... | |
static DLLAPI int ER_STDCALL | erConnectPositionerGetSync (ER_HND er_hnd) |
Get robots synchronization flag for synchronization between robot and positioner. See also erConnectPositionerSetSync() More... | |
static DLLAPI int ER_STDCALL | erConnectConveyor (ER_HND er_hnd, ER_HND er_hnd_connect) |
Connects a conveyor kinematics with handle er_hnd_connect to the robot kinematics with handle er_hnd .Remarks Use erConnectConveyorSetSync() for synchronized motion with a conveyor. Use erConnectConveyorGetSync() to receive synchronization status between robot and the connected conveyor. More... | |
static DLLAPI ER_HND ER_STDCALL | erConnectConveyorGetHND (ER_HND er_hnd) |
Get robots connection handle between robot and conveyor. See also erConnectConveyor() More... | |
static DLLAPI int ER_STDCALL | erConnectConveyorSetSync (ER_HND er_hnd, long connect_sync) |
Set robots synchronization flag for synchronization between robot and conveyor. The synchronization flag connect_sync can be one of the following values.1: ER_SYNC_OFF, 2: ER_SYNC_ON See also erConnectConveyorGetSync() More... | |
static DLLAPI int ER_STDCALL | erConnectConveyorGetSync (ER_HND er_hnd) |
Get robots synchronization flag for synchronization between robot and conveyor. See also erConnectConveyorSetSync() More... | |
static DLLAPI int ER_STDCALL | erConnectTrackMotion (ER_HND er_hnd, ER_HND er_hnd_connect) |
Connects a track motion kinematics with handle er_hnd_connect to the robot kinematics with handle er_hnd .Remarks Use erConnectTrackMotionSetSync() for synchronized motion with a track motion. Use erConnectTrackMotionGetSync() to receive synchronization status between robot and the connected track motion. More... | |
static DLLAPI ER_HND ER_STDCALL | erConnectTrackMotionGetHND (ER_HND er_hnd) |
Get robots connection handle between robot and track motion. See also erConnectTrackMotion() More... | |
static DLLAPI int ER_STDCALL | erConnectTrackMotionSetSync (ER_HND er_hnd, long connect_sync) |
Set robots synchronization flag for synchronization between robot and track motion. The synchronization flag connect_sync can be one of the following values.1: ER_SYNC_OFF, 2: ER_SYNC_ON, 4: ER_SYNC_CONVEYOR See also erConnectTrackMotionGetSync() More... | |
static DLLAPI int ER_STDCALL | erConnectTrackMotionGetSync (ER_HND er_hnd) |
Get robots synchronization flag for synchronization between robot and track motion. See also erConnectTrackMotionSetSync() More... | |
static DLLAPI int ER_STDCALL | erConnectRobot (ER_HND er_hnd, ER_HND er_hnd_connect) |
Connects a slave robot kinematics with handle er_hnd_connect to the robot kinematics with handle er_hnd .Remarks Use erConnectRobotSetSync() for synchronized motion with a slave robot. Use erConnectRobotGetSync() to receive synchronization status between robot and the connected slave robot. More... | |
static DLLAPI ER_HND ER_STDCALL | erConnectRobotGetHND (ER_HND er_hnd) |
Get robots connection handle between robot and slave robot. See also erConnectRobot() More... | |
static DLLAPI int ER_STDCALL | erConnectRobotSetSync (ER_HND er_hnd, long connect_sync) |
Set robots synchronization flag for synchronization between robot and slave robot. The synchronization flag connect_sync can be one of the following values.1: ER_SYNC_OFF, 2: ER_SYNC_ON See also erConnectRobotGetSync() More... | |
static DLLAPI int ER_STDCALL | erConnectRobotGetSync (ER_HND er_hnd) |
Get robots synchronization flag for synchronization between robot and slave robot. See also erConnectRobotSetSync() More... | |
static DLLAPI int ER_STDCALL | erUnloadTool (ER_HND er_hnd) |
Unload a kinematics tool. Unloads a kinematics tool givin by the unique kinematics handle. Unloading a kinematics tool will call callback function TerFreeGeometryProc for each geometry belonging to this kinematics tool. Remarks This kinematics handle er_hnd is still valid after calling this function. More... | |
static DLLAPI int ER_STDCALL | erLoadKin (ER_HND er_hnd, char *fln_rob) |
Load an EASY-ROB rob file (*.rob) containing a kinematics. Loading a robfile will call the callback function TerLoadGeometryProc() each time when a geometry-file-name is detected in the robfile. In this case the host application has to read or import the geometry and store it inside their own structure. Remarks Get a valid unique kinematics handle with erInitKin() In case the robfile cannot be loaded, the kinematics handle is not valid anymore. Get a new kinematics handle with erInitKin() More... | |
static DLLAPI int ER_STDCALL | erLoadTool (ER_HND er_hnd, char *fln_tool) |
Load an EASY-ROB tool file (*.tol) containing tool (tcp) data. Loading a toolfile will call the callback function TerLoadGeometryProc() each time when a geometry-file-name is detected in the toolfile. . More... | |
static DLLAPI int ER_STDCALL | erGet_n_Kin (ER_HND er_hnd) |
Get the number of loaded kinematics. More... | |
static DLLAPI int ER_STDCALL | erGet_n_Kin_IR (ER_HND er_hnd) |
Get the number of loaded kinematics with more than 3 joints and inverse kinematics. More... | |
static DLLAPI int ER_STDCALL | erGetName (ER_HND er_hnd, char *name) |
Get the name of the robot. More... | |
Static Public Attributes | |
static ERK_CAPI_ROB | erk_capi_rob |
Method class kinematics and transformations. More... | |
static ERK_CAPI_MOP | erk_capi_mop |
Method class for motion planning and -execution. More... | |
static ERK_CAPI_TOOLPATH | erk_capi_toolpath |
Method class for tool path definition. More... | |
Static Public Attributes inherited from ERK_CAPI | |
static ERK_CAPI_ADMIN | erk_capi_admin |
Method class to administrate this Robotics Simulation Kernel. More... | |
static ERK_CAPI_DEVICES | erk_capi_devices |
Method class to create, attach, update devices, for kinematics calculations and for motion planning and -execution. More... | |
static ERK_CAPI_SIM | erk_capi_sim |
Method class for simulation settings. More... | |
static ERK_CAPI_AUTOPATH | erk_capi_autopath |
Method class for collision free path planning. More... | |
static ERK_CAPI_TARGETS | erk_capi_targets |
Method class for paths and tags. More... | |
static ERK_CAPI_GEO | erk_capi_geo |
Method class to handle 3D Geometry Data. More... | |
static ERK_CAPI_SYS | erk_capi_sys |
Method class for mathematical calculations, simulation status, units. More... | |
Method class to create, attach, update devices, for kinematics calculations and for motion planning and -execution.
|
static |
Connects a conveyor kinematics with handle er_hnd_connect
to the robot kinematics with handle er_hnd
.
Remarks
Use erConnectConveyorSetSync() for synchronized motion with a conveyor.
Use erConnectConveyorGetSync() to receive synchronization status between robot and the connected conveyor.
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
[in] | er_hnd_connect | unique kinematics handle for the conveyor ER_HND |
0 | - OK |
1 | - Error, not licensed option, invalid handle |
|
static |
Get robots connection handle between robot and conveyor.
See also erConnectConveyor()
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
NULL | - not connected or error |
not | NULL - valid handle for connected device |
|
static |
Get robots synchronization flag for synchronization between robot and conveyor.
See also erConnectConveyorSetSync()
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
0 | - ER_SYNC_UNDEF - Error, synchronization not defined, robot is maybe not connected to conveyor |
1 | - ER_SYNC_OFF - synchronization is OFF |
2 | - ER_SYNC_ON - synchronization is ON |
-1 | - Error, not licensed option, invalid handle |
|
static |
Set robots synchronization flag for synchronization between robot and conveyor.
The synchronization flag connect_sync
can be one of the following values.
1: ER_SYNC_OFF, 2: ER_SYNC_ON
See also erConnectConveyorGetSync()
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
[in] | connect_sync | synchronization flag |
0 | - OK |
1 | - Error, not licensed option, invalid handle |
|
static |
Connects a positioner kinematics with handle er_hnd_connect
to the robot kinematics with handle er_hnd
.
Remarks
Use erConnectPositionerSetSync() for synchronized motion with a positioner.
Use erConnectPositionerGetSync() to receive synchronization status between robot and the connected positioner.
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
[in] | er_hnd_connect | unique kinematics handle for the positioner ER_HND |
0 | - OK |
1 | - Error, not licensed option, invalid handle |
|
static |
Get robots connection handle between robot and positioner.
See also erConnectPositioner()
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
NULL | - not connected or error |
not | NULL - valid handle for connected device |
|
static |
Get robots synchronization flag for synchronization between robot and positioner.
See also erConnectPositionerSetSync()
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
0 | - ER_SYNC_UNDEF - Error, synchronization not defined, robot is maybe not connected to positioner |
1 | - ER_SYNC_OFF - synchronization is OFF |
2 | - ER_SYNC_ON - synchronization is ON |
-1 | - Error, not licensed option, invalid handle |
|
static |
Set robots synchronization flag for synchronization between robot and positioner.
The synchronization flag connect_sync
can be one of the following values.
1: ER_SYNC_OFF, 2: ER_SYNC_ON
See also erConnectPositionerGetSync()
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
[in] | connect_sync | synchronization flag |
0 | - OK |
1 | - Error, not licensed option, invalid handle |
|
static |
Connects a slave robot kinematics with handle er_hnd_connect
to the robot kinematics with handle er_hnd
.
Remarks
Use erConnectRobotSetSync() for synchronized motion with a slave robot.
Use erConnectRobotGetSync() to receive synchronization status between robot and the connected slave robot.
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
[in] | er_hnd_connect | unique kinematics handle for the slave robot ER_HND |
0 | - OK |
1 | - Error, not licensed option, invalid handle |
|
static |
Get robots connection handle between robot and slave robot.
See also erConnectRobot()
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
NULL | - not connected or error |
not | NULL - valid handle for connected device |
|
static |
Get robots synchronization flag for synchronization between robot and slave robot.
See also erConnectRobotSetSync()
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
0 | - ER_SYNC_UNDEF - Error, synchronization not defined, robot is maybe not connected to slave robot |
1 | - ER_SYNC_OFF - synchronization is OFF |
2 | - ER_SYNC_ON - synchronization is ON |
-1 | - Error, not licensed option, invalid handle |
|
static |
Set robots synchronization flag for synchronization between robot and slave robot.
The synchronization flag connect_sync
can be one of the following values.
1: ER_SYNC_OFF, 2: ER_SYNC_ON
See also erConnectRobotGetSync()
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
[in] | connect_sync | synchronization flag |
0 | - OK |
1 | - Error, not licensed option, invalid handle |
|
static |
Connects a track motion kinematics with handle er_hnd_connect
to the robot kinematics with handle er_hnd
.
Remarks
Use erConnectTrackMotionSetSync() for synchronized motion with a track motion.
Use erConnectTrackMotionGetSync() to receive synchronization status between robot and the connected track motion.
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
[in] | er_hnd_connect | unique kinematics handle for the track motion ER_HND |
0 | - OK |
1 | - Error, not licensed option, invalid handle |
|
static |
Get robots connection handle between robot and track motion.
See also erConnectTrackMotion()
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
NULL | - not connected or error |
not | NULL - valid handle for connected device |
|
static |
Get robots synchronization flag for synchronization between robot and track motion.
See also erConnectTrackMotionSetSync()
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
0 | - ER_SYNC_UNDEF - Error, synchronization not defined, robot is maybe not connected to track motion |
1 | - ER_SYNC_OFF - synchronization is OFF |
2 | - ER_SYNC_ON - synchronization is ON |
4 | - ER_SYNC_CONVEYOR - additional synchronization with Conveyor |
-1 | - Error, not licensed option, invalid handle |
|
static |
Set robots synchronization flag for synchronization between robot and track motion.
The synchronization flag connect_sync
can be one of the following values.
1: ER_SYNC_OFF, 2: ER_SYNC_ON, 4: ER_SYNC_CONVEYOR
See also erConnectTrackMotionGetSync()
[in] | er_hnd | unique kinematics handle for the robot ER_HND |
[in] | connect_sync | synchronization flag |
0 | - OK |
1 | - Error, not licensed option, invalid handle |
|
static |
Get the number of loaded kinematics.
[in] | er_hnd | unique kinematics handle ER_HND |
0 | - Error, invalid handle |
number_of_robots |
|
static |
Get the number of loaded kinematics with more than 3 joints and inverse kinematics.
[in] | er_hnd | unique kinematics handle ER_HND |
0 | - Error, invalid handle |
number_of_robots_ir |
|
static |
|
static |
Create a unique kinematics handle.
Opcode 101, Chapter 3.4.1, Page 3-26, same as erINITIALIZE()
Initializes one instance of a robot and creates an unique kinematics handle er_hnd
belonging to a robot kinematics.
This handles is necessary to access individual data from the robot and to call other functions.
Use erLoadKin() to load an EASY-ROB rob file (*.rob) containing a kinematics.
0 | - OK |
1 | - Error, cannot create a valid handle, Option MultiKIN not licensed |
|
static |
Load an EASY-ROB rob file (*.rob) containing a kinematics.
Loading a robfile will call the callback function TerLoadGeometryProc() each time when a geometry-file-name is detected in the robfile.
In this case the host application has to read or import the geometry and store it inside their own structure.
Remarks
Get a valid unique kinematics handle with erInitKin()
In case the robfile cannot be loaded, the kinematics handle is not valid anymore. Get a new kinematics handle with erInitKin()
[in] | er_hnd | unique kinematics handle ER_HND |
[in] | fln_rob | robot file name (*.rob) |
0 | - OK |
1 | - Error, cannot load file |
|
static |
Load an EASY-ROB tool file (*.tol) containing tool (tcp) data.
Loading a toolfile will call the callback function TerLoadGeometryProc() each time when a geometry-file-name is detected in the toolfile.
.
[in] | er_hnd | unique kinematics handle ER_HND |
[in] | fln_tool | tool file name (*.tol) |
0 | - OK |
1 | - Error, cannot load file |
|
static |
Unload an instance of kinematics of the Kernel.
Unloads an instance of kinematics givin by the unique kinematics handle.
Unloading a kinematics will call callback function TerFreeGeometryProc for each geometry belonging to this kinematics.
The number of loaded kinematics will be decremented.
This kinematics handle er_hnd
is set to NULL and is not valid after calling this function.
[in,out] | er_hnd | unique kinematics handle set to NULL after successful call ER_HND |
0 | - OK |
1 | - Error |
|
static |
Unload a kinematics tool.
Unloads a kinematics tool givin by the unique kinematics handle.
Unloading a kinematics tool will call callback function TerFreeGeometryProc for each geometry belonging to this kinematics tool.
Remarks
This kinematics handle er_hnd
is still valid after calling this function.
[in] | er_hnd | unique kinematics handle ER_HND |
0 | - OK |
1 | - Error |
|
static |
Method class for motion planning and -execution.
|
static |
Method class kinematics and transformations.
|
static |
Method class for tool path definition.