EASY-ROB™ Kernel  v8.606
Static Public Member Functions | Static Public Attributes | List of all members
ERK_CAPI_DEVICES Class Reference

Method class to create, attach, update devices, for kinematics calculations and for motion planning and -execution. More...

#include <erk_capi.h>

Inheritance diagram for ERK_CAPI_DEVICES:
ERK_CAPI ERK_CAPI_MOP ERK_CAPI_ROB ERK_CAPI_TOOLPATH ERK_CAPI_MOP_DATA ERK_CAPI_MOP_EXEC ERK_CAPI_MOP_PATH ERK_CAPI_MOP_PREP ERK_CAPI_ROB_ATRIBUTES ERK_CAPI_ROB_KIN ERK_CAPI_ROB_KIN_API ERK_CAPI_TOOLPATH_APIPP ERK_CAPI_TOOLPATH_ATTRIBUTES ERK_CAPI_TOOLPATH_ATTRIBUTES_AUX ERK_CAPI_TOOLPATH_CREATE ERK_CAPI_TOOLPATH_EVENTS ERK_CAPI_TOOLPATH_EXTAX_CONVEYOR ERK_CAPI_TOOLPATH_EXTAX_POSITIONER ERK_CAPI_TOOLPATH_EXTAX_TRACKMOTION ERK_CAPI_TOOLPATH_HEAD ERK_CAPI_TOOLPATH_INSTRUCTIONS ERK_CAPI_TOOLPATH_MOTION_EXEC ERK_CAPI_TOOLPATH_MOVE_CP ERK_CAPI_TOOLPATH_MOVE_JOINT ERK_CAPI_TOOLPATH_TARGETS ERK_CAPI_TOOLPATH_TOOLBOX

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...
 

Detailed Description

Method class to create, attach, update devices, for kinematics calculations and for motion planning and -execution.

Member Function Documentation

◆ erConnectConveyor()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erConnectConveyor ( ER_HND  er_hnd,
ER_HND  er_hnd_connect 
)
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.

// Example:
long ret;
ER_HND c_er_hnd; // valid robot handle
ret = erInitKin(&c_er_hnd); // Create a unique kinematics handle
ret = erLoadKin(c_er_hnd,"a robot file name"); // Load an EASY-ROB rob file (*.rob) containing a kinematics
ER_HND er_hnd_conveyor; // valid conveyor handle
ret = erInitKin(&er_hnd_conveyor); // Create a unique kinematics handle
ret = erLoadKin(er_hnd_conveyor,"a conveyor file name"); // Load an EASY-ROB rob file (*.rob) containing a kinematics
ret = erConnectConveyor(c_er_hnd,er_hnd_conveyor); // Connects a conveyor to the robot
long sync_type = ER_SYNC_ON; // device synchronization, ER_SYNC_OFF, ER_SYNC_ON
ret = erConnectConveyorSetSync(c_er_hnd,sync_type); // Set robots synchronization flag
...
Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
[in]er_hnd_connectunique kinematics handle for the conveyor ER_HND
Return values
0- OK
1- Error, not licensed option, invalid handle

◆ erConnectConveyorGetHND()

static DLLAPI ER_HND ER_STDCALL ERK_CAPI_DEVICES::erConnectConveyorGetHND ( ER_HND  er_hnd)
static

Get robots connection handle between robot and conveyor.
See also erConnectConveyor()

Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
Return values
NULL- not connected or error
notNULL - valid handle for connected device

◆ erConnectConveyorGetSync()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erConnectConveyorGetSync ( ER_HND  er_hnd)
static

Get robots synchronization flag for synchronization between robot and conveyor.
See also erConnectConveyorSetSync()

Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
Return values
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

◆ erConnectConveyorSetSync()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erConnectConveyorSetSync ( ER_HND  er_hnd,
long  connect_sync 
)
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()

Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
[in]connect_syncsynchronization flag
Return values
0- OK
1- Error, not licensed option, invalid handle

◆ erConnectPositioner()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erConnectPositioner ( ER_HND  er_hnd,
ER_HND  er_hnd_connect 
)
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.

// Example:
long ret;
ER_HND c_er_hnd; // valid robot handle
ret = erInitKin(&c_er_hnd); // Create a unique kinematics handle
ret = erLoadKin(c_er_hnd,"a robot file name"); // Load an EASY-ROB rob file (*.rob) containing a kinematics
ER_HND er_hnd_positioner; // valid positioner handle
ret = erInitKin(&er_hnd_positioner); // Create a unique kinematics handle
ret = erLoadKin(er_hnd_positioner,"a positioner file name"); // Load an EASY-ROB rob file (*.rob) containing a kinematics
ret = erConnectPositioner(c_er_hnd,er_hnd_positioner); // Connects a positioner to the robot
long sync_type = ER_SYNC_ON; // device synchronization, ER_SYNC_OFF or ER_SYNC_ON
ret = erConnectPositionerSetSync(c_er_hnd,sync_type); // Set robots synchronization flag
...
Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
[in]er_hnd_connectunique kinematics handle for the positioner ER_HND
Return values
0- OK
1- Error, not licensed option, invalid handle

◆ erConnectPositionerGetHND()

static DLLAPI ER_HND ER_STDCALL ERK_CAPI_DEVICES::erConnectPositionerGetHND ( ER_HND  er_hnd)
static

Get robots connection handle between robot and positioner.
See also erConnectPositioner()

Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
Return values
NULL- not connected or error
notNULL - valid handle for connected device

◆ erConnectPositionerGetSync()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erConnectPositionerGetSync ( ER_HND  er_hnd)
static

Get robots synchronization flag for synchronization between robot and positioner.
See also erConnectPositionerSetSync()

Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
Return values
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

◆ erConnectPositionerSetSync()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erConnectPositionerSetSync ( ER_HND  er_hnd,
long  connect_sync 
)
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()

Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
[in]connect_syncsynchronization flag
Return values
0- OK
1- Error, not licensed option, invalid handle

◆ erConnectRobot()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erConnectRobot ( ER_HND  er_hnd,
ER_HND  er_hnd_connect 
)
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.

// Example:
long ret;
ER_HND c_er_hnd; // valid robot handle
ret = erInitKin(&c_er_hnd); // Create a unique kinematics handle
ret = erLoadKin(c_er_hnd,"a robot file name"); // Load an EASY-ROB rob file (*.rob) containing a kinematics
ER_HND er_hnd_slave_robot; // valid slave robot handle
ret = erInitKin(&er_hnd_slave_robot); // Create a unique kinematics handle
ret = erLoadKin(er_hnd_slave_robot,"a slave robot file name"); // Load an EASY-ROB rob file (*.rob) containing a kinematics
ret = erConnectConveyor(c_er_hnd,er_hnd_slave_robot); // Connects a slave robot to the robot
long sync_type = ER_SYNC_ON; // device synchronization, ER_SYNC_OFF, ER_SYNC_ON
ret = erConnectRobot(c_er_hnd,sync_type); // Set robots synchronization flag
...
Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
[in]er_hnd_connectunique kinematics handle for the slave robot ER_HND
Return values
0- OK
1- Error, not licensed option, invalid handle

◆ erConnectRobotGetHND()

static DLLAPI ER_HND ER_STDCALL ERK_CAPI_DEVICES::erConnectRobotGetHND ( ER_HND  er_hnd)
static

Get robots connection handle between robot and slave robot.
See also erConnectRobot()

Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
Return values
NULL- not connected or error
notNULL - valid handle for connected device

◆ erConnectRobotGetSync()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erConnectRobotGetSync ( ER_HND  er_hnd)
static

Get robots synchronization flag for synchronization between robot and slave robot.
See also erConnectRobotSetSync()

Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
Return values
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

◆ erConnectRobotSetSync()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erConnectRobotSetSync ( ER_HND  er_hnd,
long  connect_sync 
)
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()

Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
[in]connect_syncsynchronization flag
Return values
0- OK
1- Error, not licensed option, invalid handle

◆ erConnectTrackMotion()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erConnectTrackMotion ( ER_HND  er_hnd,
ER_HND  er_hnd_connect 
)
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.

// Example:
long ret;
ER_HND c_er_hnd; // valid robot handle
ret = erInitKin(&c_er_hnd); // Create a unique kinematics handle
ret = erLoadKin(c_er_hnd,"a robot file name"); // Load an EASY-ROB rob file (*.rob) containing a kinematics
ER_HND er_hnd_track_motion; // valid track motion handle
ret = erInitKin(&er_hnd_track_motion); // Create a unique kinematics handle
ret = erLoadKin(er_hnd_track_motion,"a track motion file name"); // Load an EASY-ROB rob file (*.rob) containing a kinematics
ret = erConnectTrackMotion(c_er_hnd,er_hnd_track_motion); // Connects a track motion to the robot
long sync_type = ER_SYNC_ON; // device synchronization, ER_SYNC_OFF, ER_SYNC_ON, ER_SYNC_CONVEYOR
ret = erConnectTrackMotion(c_er_hnd,sync_type); // Set robots synchronization flag
...
Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
[in]er_hnd_connectunique kinematics handle for the track motion ER_HND
Return values
0- OK
1- Error, not licensed option, invalid handle

◆ erConnectTrackMotionGetHND()

static DLLAPI ER_HND ER_STDCALL ERK_CAPI_DEVICES::erConnectTrackMotionGetHND ( ER_HND  er_hnd)
static

Get robots connection handle between robot and track motion.
See also erConnectTrackMotion()

Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
Return values
NULL- not connected or error
notNULL - valid handle for connected device

◆ erConnectTrackMotionGetSync()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erConnectTrackMotionGetSync ( ER_HND  er_hnd)
static

Get robots synchronization flag for synchronization between robot and track motion.
See also erConnectTrackMotionSetSync()

Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
Return values
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

◆ erConnectTrackMotionSetSync()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erConnectTrackMotionSetSync ( ER_HND  er_hnd,
long  connect_sync 
)
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()

Parameters
[in]er_hndunique kinematics handle for the robot ER_HND
[in]connect_syncsynchronization flag
Return values
0- OK
1- Error, not licensed option, invalid handle

◆ erGet_n_Kin()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erGet_n_Kin ( ER_HND  er_hnd)
static

Get the number of loaded kinematics.

Parameters
[in]er_hndunique kinematics handle ER_HND
Return values
0- Error, invalid handle
number_of_robots

◆ erGet_n_Kin_IR()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erGet_n_Kin_IR ( ER_HND  er_hnd)
static

Get the number of loaded kinematics with more than 3 joints and inverse kinematics.

Parameters
[in]er_hndunique kinematics handle ER_HND
Return values
0- Error, invalid handle
number_of_robots_ir

◆ erGetName()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erGetName ( ER_HND  er_hnd,
char *  name 
)
static

Get the name of the robot.

Parameters
[in]er_hndunique kinematics handle ER_HND
[out]namename of the robot, maximum lengths ER_MAXSTR
Return values
NULLinvalid handle

◆ erInitKin()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erInitKin ( ER_HND er_hnd,
Host_HND  host_hnd = NULL 
)
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.

Parameters
[out]er_hnda new unique kinematics handle ER_HND
[in]host_hndunique host handle Host_HND
Return values
0- OK
1- Error, cannot create a valid handle, Option MultiKIN not licensed

◆ erLoadKin()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erLoadKin ( ER_HND  er_hnd,
char *  fln_rob 
)
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()

Parameters
[in]er_hndunique kinematics handle ER_HND
[in]fln_robrobot file name (*.rob)
Return values
0- OK
1- Error, cannot load file

◆ erLoadTool()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erLoadTool ( ER_HND  er_hnd,
char *  fln_tool 
)
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.
.

Parameters
[in]er_hndunique kinematics handle ER_HND
[in]fln_tooltool file name (*.tol)
Return values
0- OK
1- Error, cannot load file

◆ erUnloadKin()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erUnloadKin ( ER_HND er_hnd)
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.

Parameters
[in,out]er_hndunique kinematics handle set to NULL after successful call ER_HND
Return values
0- OK
1- Error

◆ erUnloadTool()

static DLLAPI int ER_STDCALL ERK_CAPI_DEVICES::erUnloadTool ( ER_HND  er_hnd)
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.

Parameters
[in]er_hndunique kinematics handle ER_HND
Return values
0- OK
1- Error

Member Data Documentation

◆ erk_capi_mop

ERK_CAPI_MOP ERK_CAPI_DEVICES::erk_capi_mop
static

Method class for motion planning and -execution.

◆ erk_capi_rob

ERK_CAPI_ROB ERK_CAPI_DEVICES::erk_capi_rob
static

Method class kinematics and transformations.

◆ erk_capi_toolpath

ERK_CAPI_TOOLPATH ERK_CAPI_DEVICES::erk_capi_toolpath
static

Method class for tool path definition.


The documentation for this class was generated from the following file: