EASY-ROBâ„¢ Kernel  v8.307
 All Classes Files Functions Variables Typedefs Macros Pages
er_Kernel_main.h
Go to the documentation of this file.
1 /* ------------------------------------------------------------------------------------------
2 
3  EASY-ROB Robotics Simulation Kernel
4 
5  EASY-ROB Software GmbH
6 
7  Copyright (c) 1996 - 2021
8 
9  Date: JUL 2021
10  Version: 8.307
11 
12  Description
13  This module declares all interface functions and data types supplied in this kernel and
14  for usages in the host application. The exported functions should be also entered in
15  the modul definition file (EasySimKernel.def).
16  The DLL exports ANCI-C compatable functions.
17  The kernel is available on windows x86, x64 and on Linux.
18 
19  Beschreibung
20  Dieses Modul deklariert alle Schnittstellenfunktionen und Datentypen des Kernels zur
21  Hostanwendung. Die Funktionen, die von der DLL, exportiert werden sollen müssen
22  in die Moduldefinitionsdatei (EasySimKernel.def) eingetragen werden.
23  Die DLL exportiert ANSI-C kompatible Funktionen.
24  Der Kernel ist unter Windows x86, x64 und unter Linux verfügbar.
25 
26  Autor
27  EASY-ROB Software GmbH
28 
29  Modifications
30  26-Feb-2004 - TP,SAN - Erstellt
31  xx-Feb-2004 - SAN - Implementierung
32  10-nov-2004 - SAN - MotionPlanner Implementierung (Key "MotionPlanner")
33  12-nov-2004 - SAN -> NEW_041112
34  24-mar-2005 - SAN -> NEW_050324
35  xx-aug-2012 - SAN -> v6.004
36  1)
37  //#include "ipo_extax.h" // obsolete, use ER_EXTAX_KIN_DATA_MAX instead of EXTAX_KIN_DATA_MAX
38  const long ER_EXTAX_KIN_DATA_MAX = 12; ///< Maximum number of external axis data
39  2)
40  TARGET_TYPE_ABS changes to ER_TARGET_TYPE_ABS ///< Target w.r.t object frame
41  TARGET_TYPE_ABSJOINT changes to ER_TARGET_TYPE_ABSJOINT ///< Target single axis motion,if motion_type = JOINT --> AbsJoint
42  3)
43  erSetSpeedReductionEnable() new
44  erGetSpeedReductionEnable() new
45 
46  //structure NEXT_STEP_DATA is extended by
47  //double DistanceToDestination[DISTANCE_TO_DESTINATION]; ///< distance to destination: [0] distance [m], [1] angle [rad], [2] percentage [%], [3..] tbd
48  07-nov-2013 - SAN -> v6.303
49  class ERK_CAPI
50  13-jan-2015 - SAN -> v6.601
51  31-mar-2015 - SAN -> v6.604
52  01-jul-2015 - SAN -> v6.606
53  13-jul-2015 - SAN -> v6.608 VS-2012
54  27-jul-2015 - SAN -> v6.609 erColl_ChkCollision_res() thread save
55  22-dec-2015 - SAN -> v6.611 Support ER_MOTION_FILTER_GEO for external axis
56  13-jan-2016 - SAN -> v6.612 BugFix MultiKIN Option, erGet_n_Kin_IR()
57  18-mar-2016 - SAN -> v7.001 Major Release, MatrixLock
58  03-jun-2016 - SAN -> v7.002
59  18-jul-2016 - SAN -> v7.003 0-DOF Devices
60  17-aug-2016 - SAN -> v7.004 Famos x64
61  29-sep-2016 - SAN -> v7.005 MultiDongle
62  23-feb-2017 - SAN -> v7.301 Major PreRelease
63  10-apr-2017 - SAN -> v7.302 Major Release
64  28-sep-2017 - SAN -> v7.305 Final Release
65  10-sep-2017 - SAN -> v7.306 ToolPathIntegration ...
66  24-jan-2018 - SAN -> v7.307 Patch
67  06-apr-2018 - SAN -> v7.601 Major PreRelease
68  08-may-2018 - SAN -> v7.602 API PostProc
69  17-jul-2018 - SAN -> v7.603
70  12-nov-2018 - SAN -> v7.606 ToolPath optimization
71  01-feb-2019 - SAN -> v7.607 autopath
72  08-aug-2019 - SAN -> v8.001 Major PreRelease
73  03-sep-2019 - SAN -> v8.002 VS2017
74  17-sep-2019 - SAN -> v8.003 API-INV
75  09-dec-2019 - SAN -> v8.004 GEOMNGR
76  23-feb-2020 - SAN -> v8.005 ToolOffset
77  16-jun-2020 - SAN -> v8.007 ER_KIN_PASSIVE_JNTS = 36
78  29-jul-2020 - SAN -> v8.301 GEOMNGR integration API
79  16-dec-2020 - SAN -> v8.304 Major Release
80  30-jul-2021 - SAN -> v8.307 Additional methods to access kinematics attributes, license priority ER_LICENSE_PRIORITY_LMNGR, ER_LICENSE_PRIORITY_LOCAL
81 
82 ------------------------------------------------------------------------------------------ */
83 
84 #ifndef _er_kernel_main_h
85 #define _er_kernel_main_h
86 
87 #include "erk_capi_types.h"
88 
89 #ifdef __cplusplus
90 extern "C" {
91 #endif
92 
93 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
94 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
95 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
96 // Administrative Kernel Functions, Initialization etc.
97 // class ERK_CAPI_ADMIN
98 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
99 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
100 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
101 
106 
115 DLLAPI long ER_STDCALL erKernelSetLicensePriority(int license_priority);
116 
124 DLLAPI long ER_STDCALL erKernelGetLicensePriority(int *license_priority);
125 
133 DLLAPI long ER_STDCALL erKernelSetLicenseFile(char *license_file);
134 
141 DLLAPI long ER_STDCALL erKernelGetLicenseFile(char *license_file);
142 
168 DLLAPI long ER_STDCALL erKernelInitialize(char *HostApplicationPath, char *Sold_To_ID, long mode=0);
169 
175 DLLAPI void ER_STDCALL erKernelFree(void);
176 
182 DLLAPI long ER_STDCALL erKernelGetLicense(char *hw_id);
183 
189 DLLAPI long ER_STDCALL erKernelGetHardwareID(char *hw_id);
190 
196 DLLAPI long ER_STDCALL erKernelGetOptions(char *opt);
197 
204 
205 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
206 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
207 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
208 // Funktionen zum Aufnehmen der Call-Back Funktionen
209 // class ERK_CAPI_CALLBACKS
210 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
211 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
212 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
213 
214 /* AddToHostLog
215  Fügt dem Log der Hostanwendung einen Eintrag hinzu, oder gibt eine Statusmeldung in der
216  Statuszeile aus.
217 */
223 
224 /* Enable/Disable
225  AddToHostLog messages
226 */
246 
247 /* HostLoadGeometry
248  Fordert die Hostanwendung auf eine Geometrie aus einer Datei zu laden.
249 
250  ErHandle: Handle der Kinematik, der die Geometrie zugeordnet werden soll.
251  GeoHandle: Handle auf eine eventuell schon zuvor geladene Geomtrie der Kinematik
252  Funktioniert derzeit nicht und muss 0 sein.
253  Scaling: Skalierungsfactor mit dem die Geomtrie skaliert werden soll.
254  GeoMat: Eine Transformation zur Lagekorrektur der Geometrie.
255  FileName: Name der Datei, die geladen werden soll. Derzeit wird ein vollständiger Pfad erwartet.
256 
257  Returns: Handle auf die geladene Geomtrie. Im Fehlerfall wird 0 zurückgeliefert
258 */
265 
266 /* HostUpdateGeometry
267  Fordert die Hostanwendung auf die Kinematiktransformation der Geometrie zu aktualisieren.
268 
269  ErHandle: Handle der Kinematik, der die Geometrie zugeordnet werden soll.
270  GeoHandle: Handle auf die Geomtrie, wie von "HostLoadGeometry" geliefert.
271  KinMat: Die neue Transformation.
272 
273  Returns: Im Fehlerfall 1, ansonsten 0
274 */
281 
282 /* HostFreeGeometry
283  Fordert die Hostanwendung die Geometrie freizugeben.
284 
285  ErHandle: Handle der Kinematik, der die Geometrie zugeordnet werden soll.
286  GeoHandle: Handle auf die Geomtrie, wie von "HostLoadGeometry" geliefert.
287 
288  Returns: Im Fehlerfall 1, ansonsten 0
289 */
296 
297 /* HostGetActualTravelRanges
298  Fordert die Hostanwendung die Travel Ranges zu berechnen.
299 
300  ErHandle: Handle der Kinematik, der die Travel Ranges zugeordnet werden soll.
301 
302  Returns: Im Fehlerfall 1, ansonsten 0
303 */
310 /* HostNotify
311  Gibt Meldung an die Hostanwendung.
312 */
319 
320 /* HostGrpSync
321  GrpSync IO Hostanwendung.
322 */
328 
329 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
330 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
331 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
332 // class ERK_CAPI_DEVICES
333 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
334 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
335 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
336 
337 /* erInitKin
338  Erzeugt ein Roboter Handle
339  Return 0-OK, 1-Error
340  siehe auch erINITIALIZE
341 */
352 DLLAPI long ER_STDCALL erInitKin(ER_HND *er_hnd, Host_HND host_hnd=NULL);
353 
354 /* erUnloadKin
355  Unload Robot Handle
356  Return 0-OK, 1-Error
357 */
367 DLLAPI long ER_STDCALL erUnloadKin(ER_HND *er_hnd);
368 
369 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
370 //
371 // erConnect* NEW_050402
372 //
373 // erConnectPositioner erConnectPositionerSetSync erConnectPositionerGetSync
374 // erConnectConveyor erConnectConveyorSetSync erConnectConveyorGetSync
375 // erConnectTrackMotion erConnectTrackMotionSetSync erConnectTrackMotionGetSync
376 // erConnectRobot erConnectRobotSetSync erConnectRobotGetSync
377 //
378 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
379 /* erConnectPositioner
380  Connects Positioner Kinematik mit dem Handle 'er_hnd_connect' zum Roboter mit dem Handle 'er_hnd'
381  Return 0-OK, 1-Error
382 */
408 DLLAPI long ER_STDCALL erConnectPositioner(ER_HND er_hnd, ER_HND er_hnd_connect);
416 
417 /* erConnectPositionerSetSync
418  Setzt Sync Flag der Positioner Kinematik
419  Return 0-OK, 1-Error
420 */
430 DLLAPI long ER_STDCALL erConnectPositionerSetSync(ER_HND er_hnd, long connect_sync);
431 
432 /* erConnectPositionerGetSync
433  Liest Sync Flag der Positioner Kinematik
434  Return -1-Error, ER_SYNC_UNDEF, ER_SYNC_OFF, ER_SYNC_ON
435 */
445 
446 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
447 /* erConnectConveyor
448  Connects Conveyor Kinematik mit dem Handle 'er_hnd_connect' zum Roboter mit dem Handle 'er_hnd'
449  Return 0-OK, 1-Error
450 */
476 DLLAPI long ER_STDCALL erConnectConveyor(ER_HND er_hnd, ER_HND er_hnd_connect);
484 
485 /* erConnectConveyorSetSync
486  Setzt Sync Flag der Conveyor Kinematik
487  Return 0-OK, 1-Error
488 */
498 DLLAPI long ER_STDCALL erConnectConveyorSetSync(ER_HND er_hnd, long connect_sync);
499 
500 /* erConnectConveyorGetSync
501  Liest Sync Flag der Conveyor Kinematik
502  Return -1-Error, ER_SYNC_UNDEF, ER_SYNC_OFF, ER_SYNC_ON
503 */
513 
514 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
515 /* erConnectTrackMotion
516  Connects Track Kinematik mit dem Handle 'er_hnd_connect' zum Roboter mit dem Handle 'er_hnd'
517  Return 0-OK, 1-Error
518 */
544 DLLAPI long ER_STDCALL erConnectTrackMotion(ER_HND er_hnd, ER_HND er_hnd_connect);
552 
553 /* erConnectTrackMotionSetSync
554  Setzt Sync Flag der TrackMotion Kinematik
555  Return 0-OK, 1-Error
556 */
566 DLLAPI long ER_STDCALL erConnectTrackMotionSetSync(ER_HND er_hnd, long connect_sync);
567 /* erConnectTrackMotionGetSync
568  Liest Sync Flag der TrackMotion Kinematik
569  Return -1-Error, ER_SYNC_UNDEF, ER_SYNC_OFF, ER_SYNC_ON, ER_SYNC_CONVEYOR
570 */
581 
582 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
583 /* erConnectRobot
584  Connects Robot Kinematik mit dem Handle 'er_hnd_connect' zum Roboter mit dem Handle 'er_hnd'
585  Return 0-OK, 1-Error
586 */
612 DLLAPI long ER_STDCALL erConnectRobot(ER_HND er_hnd, ER_HND er_hnd_connect);
620 
621 /* erConnectRobotSetSync
622  Setzt Sync Flag der Robot Kinematik
623  Return 0-OK, 1-Error
624 */
634 DLLAPI long ER_STDCALL erConnectRobotSetSync(ER_HND er_hnd, long connect_sync);
635 /* erConnectRobotGetSync
636  Liest Sync Flag der Robot Kinematik
637  Return -1-Error, ER_SYNC_UNDEF, ER_SYNC_OFF, ER_SYNC_ON
638 */
648 
649 /* erUnloadTool
650  Loescht Tool GeoHandle und setzt Tool auf Ident
651  Important:
652  Damit die TCP Position stimmt, muss ein rob_kin_update() folgen
653  Return 0-OK, 1-Error
654 */
664 DLLAPI long ER_STDCALL erUnloadTool(ER_HND er_hnd);
665 
666 /* erLoadKin
667  Load an easy-rob robot file with tool
668  Return 0-OK, 1-Error oder Abort
669 */
681 DLLAPI long ER_STDCALL erLoadKin(ER_HND er_hnd,char *fln_rob);
682 
683 /* erLoadTool
684  Load an easy-rob tool file
685  Return 0-OK, 1-Error oder Abort
686 */
694 DLLAPI long ER_STDCALL erLoadTool(ER_HND er_hnd,char *fln_tool);
695 
696 /* erGet_n_Kin
697  Return Number of loaded Robots "m_n_rob_kin"
698 */
704 DLLAPI long ER_STDCALL erGet_n_Kin(ER_HND er_hnd);
705 
706 /* erGet_n_Kin_IR
707  Return Number of loaded Robots with more than 3 joints and inverse kinematics "m_n_rob_kin_ir"
708 */
715 
716 /* erGetName
717  Name of Robot
718  Return 0-OK, 1-Error oder Abort
719 */
725 DLLAPI long ER_STDCALL erGetName(ER_HND er_hnd,char *name);
726 
727 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
728 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
729 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
730 // Robot Kinematics
731 // class ERK_CAPI_ROB_KIN
732 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
733 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
734 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
735 
736 /* erGetIDs
737  Kinematik ID - kinematischer Typ
738  RRRRRR_id =1; // Manutec
739  TTTRRR_id =2; // Portal
740  RRRRRR_bl_id =3; // ABB back link
741  UNIV_ROB_id =10; // Universelle Koordinaten
742  DH_id =11; // DH Koordinaten
743  inv_id - ID fuer inverse Kineamtik
744  inv_sub_id - Sub ID fuer inverse Kineamtik
745  Return 0-OK, 1-Error oder Abort
746 */
759 DLLAPI long ER_STDCALL erGetIDs(ER_HND er_hnd,long *kin_id,long *inv_id, long *inv_sub_id);
760 
761 /* erGet_num_dofs
762  Return Number of Robot active joints
763 */
770 
771 /* erGet_num_dofs_passive
772  Return Number of Robot passive joints
773 */
780 
781 /* erGetJointTypes
782  gets type of active robot joints 0-Rot 1-Trans
783  Return 0-OK, 1-Error oder Abort
784 */
793 DLLAPI long ER_STDCALL erGetJointTypes(ER_HND er_hnd, long *jnt_type_active);
794 
795 /* erGetJointTypes_passive
796  gets type of passive robot joints 0-Rot 1-Trans
797  Return 0-OK, 1-Error oder Abort
798 */
807 DLLAPI long ER_STDCALL erGetJointTypes_passive(ER_HND er_hnd, long *jnt_type_passive);
808 
809 /* erGetJointDirections
810  gets direction of active robot joints 1-JNT_DIRECTION_X, 2-JNT_DIRECTION_Y, 3-JNT_DIRECTION_Z
811  Return 0-OK, 1-Error oder Abort
812 */
821 DLLAPI long ER_STDCALL erGetJointDirections(ER_HND er_hnd, long *jnt_direction_active);
822 
823 /* erGetJointDirections_passive
824  gets type direction of passive robot joints 1-JNT_DIRECTION_X, 2-JNT_DIRECTION_Y, 3-JNT_DIRECTION_Z
825  Return 0-OK, 1-Error oder Abort
826 */
835 DLLAPI long ER_STDCALL erGetJointDirections_passive(ER_HND er_hnd, long *jnt_direction_passive);
836 
837 /* erGetJointChainTypes
838  gets chain type of active robot joints 1-JNT_CHAIN_TYPE_CHAIN, 2-JNT_CHAIN_TYPE_NO_CHAIN, 3-JNT_CHAIN_TYPE_SEP_NO_CHAIN
839  Return 0-OK, 1-Error or Abort
840 */
848 DLLAPI long ER_STDCALL erGetJointChainTypes(ER_HND er_hnd, long *jnt_chain_type_active);
849 
850 /* erGetJointChainTypes_passive
851  gets chain type of passive robot joints 1-JNT_CHAIN_TYPE_CHAIN, 2-JNT_CHAIN_TYPE_NO_CHAIN, 3-JNT_CHAIN_TYPE_SEP_NO_CHAIN
852  Return 0-OK, 1-Error or Abort
853 */
861 DLLAPI long ER_STDCALL erGetJointChainTypes_passive(ER_HND er_hnd, long *jnt_chain_type_passive);
862 
863 /* erGetJointAttachDof_active
864  gets Attach-Dof of active robot joints
865  Return 0-OK, 1-Error or Abort
866 */
876 DLLAPI long ER_STDCALL erGetJointAttachDof_active(ER_HND er_hnd, long *jnt_attach_dof_active);
877 
878 /* erGetJointAttachDof_passive
879  gets Attach-Dof of passive robot joints
880  Return 0-OK, 1-Error or Abort
881 */
890 DLLAPI long ER_STDCALL erGetJointAttachDof_passive(ER_HND er_hnd, long *jnt_attach_dof_passive);
891 
892 /* erGetMoveBaseMode
893  gets moveable base mode 0-Robot base is fix (default), 1-Robot base is moveable
894  Return 0-OK, 1-Error oder Abort
895 */
905 DLLAPI long ER_STDCALL erGetMoveBaseMode(ER_HND er_hnd,long *move_base_mode);
906 
907 /* erGetMoveBasepJointIdx
908  gets passive joint idx representing the moveable base
909  0-Robot base is fix (default)
910  n-index of passive joint representing the moveable base
911  Return 0-OK, 1-Error oder Abort
912 */
921 DLLAPI long ER_STDCALL erGetMoveBasepJointIdx(ER_HND er_hnd,long *move_base_pjointidx);
922 
923 /* erGetpJointMoveBase
924  get transformation from passive joint 'pjnt' to the moveable base 'mb'
925  Return 0-OK, 1-Error oder Abort
926 */
935 DLLAPI long ER_STDCALL erGetpJointMoveBase(ER_HND er_hnd,DFRAME *pjntTmb);
936 
937 /* erGetRobotBaseToMoveBase
938  get transformation from robot base 'b' to the moveable base 'mb'
939  bTmb is Ident, if moveable base is fix
940  Return 0-OK, 1-Error oder Abort
941 */
951 
952 /* erSetJoints
953  Set Robot joints
954  Return 0-OK, 1-Error oder Abort
955 */
964 DLLAPI long ER_STDCALL erSetJoints(ER_HND er_hnd,double *q_solut);
965 
966 /* erSetJoint
967  Set Robot joint
968  Return 0-OK, 1-Error oder Abort
969 */
980 DLLAPI long ER_STDCALL erSetJoint(ER_HND er_hnd,double q_solut, long jnt_no);
981 
982 /* erGetJoints
983  Get current (active) Robot joints
984  Return 0-OK, 1-Error oder Abort
985 */
997 DLLAPI long ER_STDCALL erGetJoints(ER_HND er_hnd,double *q_solut);
998 
999 /* erGetJointSolutions
1000  Get all (active) Robot joints solutions
1001  Return 0-OK, 1-Error oder Abort
1002 */
1051 DLLAPI long ER_STDCALL erGetJointSolutions(ER_HND er_hnd,double *q_solutions, long *q_warnings);
1052 
1053 /* erGetJointSpeeds
1054  Get current (active) Robot joint speeds
1055  Return 0-OK, 1-Error oder Abort
1056 */
1066 DLLAPI long ER_STDCALL erGetJointSpeeds(ER_HND er_hnd,double *v_solut);
1067 
1068 /* erGetJointAccels
1069  Get current (active) Robot joint accels
1070  Return 0-OK, 1-Error oder Abort
1071 */
1081 DLLAPI long ER_STDCALL erGetJointAccels(ER_HND er_hnd,double *a_solut);
1082 
1083 /* erGetJoints_passive
1084  Get current passive Robot joints
1085 */
1095 DLLAPI long ER_STDCALL erGetJoints_passive(ER_HND er_hnd,double *q_passive);
1096 
1097 /* erSetConfig
1098  Set Robot configuration
1099 */
1112 DLLAPI long ER_STDCALL erSetConfig(ER_HND er_hnd, long config);
1113 
1114 /* erGetConfig
1115  Set Robot configuration
1116 */
1125 DLLAPI long ER_STDCALL erGetConfig(ER_HND er_hnd, long *config);
1126 
1127 /* erFindConfig
1128  Find current Robot configuration
1129 */
1140 DLLAPI long ER_STDCALL erFindConfig(ER_HND er_hnd, long *config);
1141 
1142 /* erGetNumConfigs
1143  Get Number of Robot configurations
1144 */
1151 DLLAPI long ER_STDCALL erGetNumConfigs(ER_HND er_hnd, long *num_configs);
1152 
1153 /* erInvKinRobotBaseTip
1154  Inverse bTt is Robot base to Tip
1155  Return:
1156  Return code for inverse kinematics, INV_WARN_*
1157 */
1172 
1173 /* erInvKinWorldTip
1174  Inverse iTt is World to Tip
1175  Return:
1176  Return code for inverse kinematics, INV_WARN_*
1177 */
1191 DLLAPI long ER_STDCALL erInvKinWorldTip(ER_HND er_hnd,DFRAME *iTt);
1192 
1193 /* erInvKinRobotBaseTcp
1194  Inverse bTt is Robot base to Tcp
1195  Return:
1196  Return code for inverse kinematics, INV_WARN_*
1197 */
1212 
1213 /* erInvKinWorldTcp
1214  Inverse iTt is World to Tcp
1215  Return:
1216  Return code for inverse kinematics, INV_WARN_*
1217 */
1231 DLLAPI long ER_STDCALL erInvKinWorldTcp(ER_HND er_hnd,DFRAME *iTw);
1232 
1233 /* erSetTool
1234  Set Tool Tip to Tcp
1235 */
1242 DLLAPI long ER_STDCALL erSetTool(ER_HND er_hnd,DFRAME *tTw);
1243 /* erGetTool
1244  Get Tool Tip to Tcp
1245 */
1259 DLLAPI long ER_STDCALL erGetTool(ER_HND er_hnd,DFRAME *tTw);
1260 
1261 /* erSetBaseRobotBase
1262  Set Base w.r.t. RobotBase
1263 */
1272 DLLAPI long ER_STDCALL erSetBaseRobotBase(ER_HND er_hnd,DFRAME *bTbase);
1273 
1274 /* erGetBaseRobotBase
1275  Get Base w.r.t. RobotBase
1276 */
1285 DLLAPI long ER_STDCALL erGetBaseRobotBase(ER_HND er_hnd,DFRAME *bTbase);
1286 
1287 /* erSetBaseWorld
1288  Set Base w.r.t. World
1289 */
1298 DLLAPI long ER_STDCALL erSetBaseWorld(ER_HND er_hnd,DFRAME *iTbase);
1299 
1300 /* erGetBaseWorld
1301  Get Base w.r.t. World
1302 */
1311 DLLAPI long ER_STDCALL erGetBaseWorld(ER_HND er_hnd,DFRAME *iTbase);
1312 
1313 /* erSetRobotBase
1314  Set RobotBase, World to Robot base
1315 */
1322 DLLAPI long ER_STDCALL erSetRobotBase(ER_HND er_hnd,DFRAME *iTb);
1323 
1324 /* erGetRobotBase
1325  Get RobotBase, World to Robot base
1326 */
1340 DLLAPI long ER_STDCALL erGetRobotBase(ER_HND er_hnd,DFRAME *iTb);
1341 
1342 /* erGetRobotBaseTip
1343  Get Robot Tip w.r.t. Robot base
1344 */
1351 DLLAPI long ER_STDCALL erGetRobotBaseTip(ER_HND er_hnd,DFRAME *bTt);
1352 /* erGetRobotBaseTcp
1353  Get Robot Tcp w.r.t. Robot base
1354 */
1361 DLLAPI long ER_STDCALL erGetRobotBaseTcp(ER_HND er_hnd,DFRAME *bTw);
1362 
1363 /* erGetWorldTip
1364  Get Robot Tip w.r.t. World
1365 */
1372 DLLAPI long ER_STDCALL erGetWorldTip(ER_HND er_hnd,DFRAME *iTt);
1373 
1374 /* erGetWorldTcp
1375  Get Robot Tcp w.r.t. World
1376 */
1383 DLLAPI long ER_STDCALL erGetWorldTcp(ER_HND er_hnd,DFRAME *iTw);
1384 
1385 /* erUpdateKin
1386  Update the complete kinematic
1387 */
1396 DLLAPI long ER_STDCALL erUpdateKin(ER_HND er_hnd);
1397 
1398 /* erGetJointFrameRobotBase
1399  Transformation from RobotBase to (active) Robot Joint
1400  Return 0-OK, 1-Error oder Abort
1401 */
1410 DLLAPI long ER_STDCALL erGetJointFrameRobotBase(ER_HND er_hnd,long active_jnt_no,DFRAME *bTax);
1411 
1412 /* erGetJointFrameRobotBase_passive
1413  Transformation from RobotBase to passive Robot Joint
1414  Return 0-OK, 1-Error oder Abort
1415 */
1424 DLLAPI long ER_STDCALL erGetJointFrameRobotBase_passive(ER_HND er_hnd,long passive_jnt_no,DFRAME *bTax);
1425 
1426 /* erGetJointFrameWorld
1427  Transformation from World to (active) Robot Joint
1428  Return 0-OK, 1-Error oder Abort
1429 */
1438 DLLAPI long ER_STDCALL erGetJointFrameWorld(ER_HND er_hnd,long active_jnt_no,DFRAME *iTax);
1439 
1440 /* erGetJointFrameWorld_passive
1441  Transformation from World to passive Robot Joint
1442  Return 0-OK, 1-Error oder Abort
1443 */
1452 DLLAPI long ER_STDCALL erGetJointFrameWorld_passive(ER_HND er_hnd,long passive_jnt_no,DFRAME *iTax);
1453 
1454 /* erSetExtTcpRobotBase
1455  Set external Tcp w.r.t Robot Base
1456  Return 0-OK, 1-Error oder Abort
1457  Ausnahme: Beim Positioner ist der external Tcp w.r.t flange des positioners
1458 */
1467 DLLAPI long ER_STDCALL erSetExtTcpRobotBase(ER_HND er_hnd,DFRAME *bText, long use_ext_flange);
1468 
1469 /* erGetExtTcpRobotBase
1470  Get external Tcp w.r.t. Robot Base
1471  Return 0-OK, 1-Error oder Abort
1472 */
1479 DLLAPI long ER_STDCALL erGetExtTcpRobotBase(ER_HND er_hnd,DFRAME *bText);
1480 
1481 /* erSetExtTcpWorld
1482  Set external Tcp w.r.t world
1483  Return 0-OK, 1-Error oder Abort
1484 */
1491 DLLAPI long ER_STDCALL erSetExtTcpWorld(ER_HND er_hnd,DFRAME *iText);
1492 
1493 /* erGetExtTcpWorld
1494  Get external Tcp w.r.t. world
1495  Return 0-OK, 1-Error oder Abort
1496 */
1503 DLLAPI long ER_STDCALL erGetExtTcpWorld(ER_HND er_hnd,DFRAME *iText);
1504 
1505 /* erSetExtTcpMode
1506  Set ExtTcpMode 0-IPO_MODE_BASE (Werk ZEUG fuehrend), 1-IPO_MODE_TOOL (Werk STUECK fuehren)
1507  Return 0-OK, 1-Error oder Abort
1508 */
1516 DLLAPI long ER_STDCALL erSetExtTcpMode(ER_HND er_hnd,long ext_tcp_mode);
1517 
1518 /* erGetExtTcpMode
1519  Get ExtTcpMode 0-IPO_MODE_BASE (Werk ZEUG fuehrend), 1-IPO_MODE_TOOL (Werk STUECK fuehren)
1520  Return 0-OK, 1-Error oder Abort
1521 */
1529 DLLAPI long ER_STDCALL erGetExtTcpMode(ER_HND er_hnd,long *ext_tcp_mode);
1530 
1531 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1532 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1533 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1534 // Robot Kinematics API
1535 // class ERK_CAPI_ROB_KIN_API
1536 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1537 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1538 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1539 
1540 /* erGetInvKinID
1541  Inverse kinematics ID for cRobot
1542  Return 0-OK, 1-Error oder Abort
1543 */
1550 DLLAPI long ER_STDCALL erGetInvKinID(ER_HND er_hnd, long *invkin_id);
1551 
1552 /* erGetInvKinSubID
1553  Inverse kinematics Sub-ID for cRobot
1554  Return 0-OK, 1-Error oder Abort
1555 */
1562 DLLAPI long ER_STDCALL erGetInvKinSubID(ER_HND er_hnd, long *invkinsub_id);
1563 
1580 DLLAPI long ER_STDCALL erSetJointSolutions(ER_HND er_hnd, double *q_solutions, long *q_warnings);
1581 
1592 DLLAPI long ER_STDCALL erSetJointDyn(ER_HND er_hnd, double q_dyn, long jnt_no);
1593 
1595 DLLAPI long ER_STDCALL erGetJointFrameActiveNext(ER_HND er_hnd, long active_jnt_no, DFRAME *T);
1596 DLLAPI long ER_STDCALL erSetJointFrameActiveNext(ER_HND er_hnd, long active_jnt_no, DFRAME *T);
1597 DLLAPI long ER_STDCALL erGetJointFrameActiveLast(ER_HND er_hnd, long active_jnt_no, DFRAME *T);
1598 DLLAPI long ER_STDCALL erSetJointFrameActiveLast(ER_HND er_hnd, long active_jnt_no, DFRAME *T);
1599 
1600 DLLAPI long ER_STDCALL erGetJointFramePassiveNext(ER_HND er_hnd, long passive_jnt_no, DFRAME *T);
1601 DLLAPI long ER_STDCALL erSetJointFramePassiveNext(ER_HND er_hnd, long passive_jnt_no, DFRAME *T);
1602 DLLAPI long ER_STDCALL erGetJointFramePassiveLast(ER_HND er_hnd, long passive_jnt_no, DFRAME *T);
1603 DLLAPI long ER_STDCALL erSetJointFramePassiveLast(ER_HND er_hnd, long passive_jnt_no, DFRAME *T);
1605 
1606 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1607 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1608 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1609 // Robot Attributes
1610 // class ERK_CAPI_ROB_ATRIBUTES
1611 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1612 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1613 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1614 
1615 
1616 /* erSetHomepos
1617  Set Robot Home position
1618 */
1628 DLLAPI long ER_STDCALL erSetHomepos(ER_HND er_hnd,double *homepos);
1629 
1630 /* erGetHomepos
1631  Get Robot Home position
1632 */
1642 DLLAPI long ER_STDCALL erGetHomepos(ER_HND er_hnd,double *homepos);
1643 
1644 /* erSetSweMin
1645  Set Robot min. SWE Switch
1646 */
1656 DLLAPI long ER_STDCALL erSetSweMin(ER_HND er_hnd,double *swe_min);
1657 
1658 /* erGetSweMin
1659  Get min. SWE Switch
1660 */
1670 DLLAPI long ER_STDCALL erGetSweMin(ER_HND er_hnd,double *swe_min);
1671 
1672 /* erGetSweMinCalc
1673  Get min. calculated SWE Switch
1674 */
1685 DLLAPI long ER_STDCALL erGetSweMinCalc(ER_HND er_hnd,double *swe_min_calc);
1686 
1687 /* erSetSweMax
1688  Set max. SWE Switch
1689 */
1699 DLLAPI long ER_STDCALL erSetSweMax(ER_HND er_hnd,double *swe_max);
1700 
1701 /* erGetSweMax
1702  Get max. SWE Switch
1703 */
1713 DLLAPI long ER_STDCALL erGetSweMax(ER_HND er_hnd,double *swe_max);
1714 /* erGetSweMaxCalc
1715  Get max. calculated SWE Switch
1716 */
1727 DLLAPI long ER_STDCALL erGetSweMaxCalc(ER_HND er_hnd,double *swe_max_calc);
1728 
1729 /* erGetSweMinMaxCalc
1730  Get min. and max. calculated SWE Switches
1731 */
1743 DLLAPI long ER_STDCALL erGetSweMinMaxCalc(ER_HND er_hnd,double *swe_min_calc,double *swe_max_calc);
1744 
1752 DLLAPI long ER_STDCALL erGetSweCalcMode(ER_HND er_hnd,long *swe_calc_mode);
1753 
1754 /* erSetSweMin_passive
1755  Set Robot min. SWE Switch for passive joints
1756 */
1766 DLLAPI long ER_STDCALL erSetSweMin_passive(ER_HND er_hnd, double *swe_min_passive);
1767 /* erGetSweMin_passive
1768  Get min. SWE Switch from passive joints
1769 */
1779 DLLAPI long ER_STDCALL erGetSweMin_passive(ER_HND er_hnd, double *swe_min_passive);
1780 
1781 /* erSetSweMax_passive
1782  Set Robot max. SWE Switch for passive joints
1783 */
1793 DLLAPI long ER_STDCALL erSetSweMax_passive(ER_HND er_hnd, double *swe_max_passive);
1794 /* erGetSweMax_passive
1795  Get max. SWE Switch from passive joints
1796 */
1806 DLLAPI long ER_STDCALL erGetSweMax_passive(ER_HND er_hnd, double *swe_max_passive);
1807 
1808 /* erGetConfigName
1809  Name of robot configuration
1810  Return 0-OK, 1-Error oder Abort
1811 */
1819 DLLAPI long ER_STDCALL erGetConfigName(ER_HND er_hnd, long config_idx, char *config_name);
1820 
1821 /* erGetJointName
1822  Name of active robot joint
1823  Return 0-OK, 1-Error oder Abort
1824 */
1831 DLLAPI long ER_STDCALL erGetJointName(ER_HND er_hnd, long active_jnt_no, char *jnt_name);
1832 
1833 /* erGetJointName_passive
1834  Name of passive robot joint
1835  Return 0-OK, 1-Error oder Abort
1836 */
1843 DLLAPI long ER_STDCALL erGetJointName_passive(ER_HND er_hnd, long passive_jnt_no, char *jnt_name_passive);
1844 
1845 
1846 /* erSetJointSign
1847  Set Joint Directions
1848 */
1856 DLLAPI long ER_STDCALL erSetJointSign(ER_HND er_hnd,double *joint_sign); // NEW_050324
1857 
1858 /* erGetJointSign
1859  Get Joint Sign
1860 */
1869 DLLAPI long ER_STDCALL erGetJointSign(ER_HND er_hnd,double *joint_sign); // NEW_050324
1870 
1871 /* erSetJointOffset
1872  Set Joint Offsets
1873 */
1881 DLLAPI long ER_STDCALL erSetJointOffset(ER_HND er_hnd,double *joint_offset); // NEW_050324
1882 
1883 /* erGetJointOffset
1884  Get Joint Offsets
1885 */
1893 DLLAPI long ER_STDCALL erGetJointOffset(ER_HND er_hnd,double *joint_offset); // NEW_050324
1894 
1895 /* erSetVqMax
1896  Set max. joint speed [rad/s,m/s]
1897 */
1905 DLLAPI long ER_STDCALL erSetVqMax(ER_HND er_hnd,double *vq_max);
1906 
1907 /* erGetVqMax
1908  Get max. joint speed [rad/s,m/s]
1909 */
1917 DLLAPI long ER_STDCALL erGetVqMax(ER_HND er_hnd,double *vq_max);
1918 
1919 /* erSetAqMax
1920  Set max. joint acceleration [rad/s^2,m/s^2]
1921 */
1929 DLLAPI long ER_STDCALL erSetAqMax(ER_HND er_hnd,double *aq_max);
1930 
1931 /* erGetAqMax
1932  Get max. joint acceleration [rad/s^2,m/s^2]
1933 */
1941 DLLAPI long ER_STDCALL erGetAqMax(ER_HND er_hnd,double *aq_max);
1942 
1943 /* erSetVxMax
1944  Set max. cartesian speed [m/s]
1945 */
1952 DLLAPI long ER_STDCALL erSetVxMax(ER_HND er_hnd,double vx_max);
1953 
1954 /* erGetVxMax
1955  Get max. cartesian speed [m/s]
1956 */
1963 DLLAPI long ER_STDCALL erGetVxMax(ER_HND er_hnd,double *vx_max);
1964 
1965 /* erSetVxOriMax
1966  Set max. cartesian orientation speed [rad/s]
1967 */
1974 DLLAPI long ER_STDCALL erSetVxOriMax(ER_HND er_hnd,double vx_ori_max);
1975 
1976 /* erGetVxOriMax
1977  Get max. cartesian orientation orientation speed [rad/s]
1978 */
1985 DLLAPI long ER_STDCALL erGetVxOriMax(ER_HND er_hnd,double *vx_ori_max);
1986 
1987 /* erSetAxMax
1988  Set max. cartesian acceleration [m/s^2]
1989 */
1996 DLLAPI long ER_STDCALL erSetAxMax(ER_HND er_hnd,double ax_max);
1997 
1998 /* erGetAxMax
1999  Get max. cartesian acceleration [m/s^2]
2000 */
2007 DLLAPI long ER_STDCALL erGetAxMax(ER_HND er_hnd,double *ax_max);
2008 
2009 /* erSetAxOriMax
2010  Set max. cartesian orientation acceleration [rad/s^2]
2011 */
2019 DLLAPI long ER_STDCALL erSetAxOriMax(ER_HND er_hnd,double ax_ori_max);
2020 /* erGetAxOriMax
2021  Get max. cartesian orientation acceleration [rad/s^2]
2022 */
2029 DLLAPI long ER_STDCALL erGetAxOriMax(ER_HND er_hnd,double *ax_ori_max);
2030 
2031 /* erGetBackLink obsolete -> use erGetBacklink(...)
2032  Get Back Link returns robot back link information
2033  *backlink = 0-KIN_BACK_LINK_NO | 1-KIN_BACK_LINK_YES | 2-KIN_BACK_LINK_UNKNOWN
2034  Return 0-OK, 1-Error oder Abort
2035 */
2038 DLLAPI long ER_STDCALL erGetBackLink(ER_HND er_hnd,long *backlink); // obsolete -> use erGetBacklink(...)
2039 
2040 /* erSetBacklink
2041  Set Backlink extended attribute
2042 */
2052 DLLAPI long ER_STDCALL erSetBacklink(ER_HND er_hnd,long backlink);
2053 
2054 /* erGetBacklink
2055  Get Backlink extended attribute
2056 */
2066 DLLAPI long ER_STDCALL erGetBacklink(ER_HND er_hnd,long *backlink);
2067 
2068 /* erSetAxis_couplingA2A3
2069  Set Axis_couplingA2A3 extended attribute
2070 */
2080 DLLAPI long ER_STDCALL erSetAxis_couplingA2A3(ER_HND er_hnd,long axis_couplingA2A3);
2081 
2082 /* erGetAxis_couplingA2A3
2083  Get Axis_couplingA2A3 extended attribute
2084 */
2094 DLLAPI long ER_STDCALL erGetAxis_couplingA2A3(ER_HND er_hnd,long *axis_couplingA2A3);
2095 
2096 /* erSetCounter_weight
2097  Set Counter_weight extended attribute
2098 */
2108 DLLAPI long ER_STDCALL erSetCounter_weight(ER_HND er_hnd,long counter_weight);
2109 
2110 /* erGetCounter_weight
2111  Get Counter_weight extended attribute
2112 */
2122 DLLAPI long ER_STDCALL erGetCounter_weight(ER_HND er_hnd,long *counter_weight);
2123 
2124 /* erSetTurn_interval
2125  Set Turn_interval [rad,m]
2126 */
2137 DLLAPI long ER_STDCALL erSetTurn_interval(ER_HND er_hnd,double *turn_interval);
2138 
2139 /* erGetTurn_interval
2140  Get Turn_interval [rad,m]
2141 */
2152 DLLAPI long ER_STDCALL erGetTurn_interval(ER_HND er_hnd,double *turn_interval);
2153 
2154 /* erSetTurn_offset
2155  Set Turn_offset [rad,m]
2156 */
2167 DLLAPI long ER_STDCALL erSetTurn_offset(ER_HND er_hnd,double *turn_offset);
2168 
2169 /* erGetTurn_offset
2170  Get Turn_offset [rad,m]
2171 */
2182 DLLAPI long ER_STDCALL erGetTurn_offset(ER_HND er_hnd,double *turn_offset);
2183 
2184 /* erSetTurn_value
2185  Set Turn_value, will set turn_enable
2186 */
2199 DLLAPI long ER_STDCALL erSetTurn_value(ER_HND er_hnd,long *turn_value);
2200 
2201 /* erGetTurn_value
2202  Get Turn_value
2203 */
2214 DLLAPI long ER_STDCALL erGetTurn_value(ER_HND er_hnd,long *turn_value);
2215 
2216 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2217 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2218 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2219 // MotionPlanner
2220 // class ERK_CAPI_MOP
2221 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2222 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2223 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2224 
2225 /* erINITIALIZE
2226  Erzeugt ein Roboter Handle
2227  Opcode 101, Chapter 3.4.1, Page 3-26
2228  Return 0-OK, 1-Error
2229  entspricht erInitKin()
2230 */
2240 DLLAPI long ER_STDCALL erINITIALIZE (ER_HND *er_hnd, Host_HND host_hnd=NULL);
2241 
2242 /* erRESET
2243  Definition: Resets an instance of a robot to an initial state
2244  Opcode 102, Chapter 3.4.1, Page 3-29
2245  Return 0-OK, 1-Error
2246 */
2268 DLLAPI long ER_STDCALL erRESET(ER_HND er_hnd);
2269 
2270 /* erTERMINATE
2271  Loescht Roboter Handle
2272  Definition: Terminates an instance of a robot of the Kernel
2273  Opcode 103, Chapter 3.4.1, Page 3-30
2274  Return 0-OK, 1-Error
2275  see erUnloadKin()
2276 */
2285 DLLAPI long ER_STDCALL erTERMINATE(ER_HND *er_hnd);
2286 
2287 /* erSET_INITIAL_POSITION
2288  sets the robot model to a position according to the input data
2289  Opcode 116, Chapter 3.4.3, Page 3-50
2290  Return 0-OK, 1-Error
2291 */
2301 DLLAPI long ER_STDCALL erSET_INITIAL_POSITION(ER_HND er_hnd, INITIAL_POSITION_DATA *p_initial_position_data);
2302 
2303 /*erSELECT_TRACKING
2304  Definition: Selects the Tracking On or Off in the Kernel
2305  Opcode 146, Chapter 3.4.7, Page 3-93
2306  Return 0-OK, 1-Error, -1- not supported
2307 */
2319 DLLAPI long ER_STDCALL erSELECT_TRACKING(ER_HND er_hnd, long conveyor_flags);
2320 
2321 /*erSET_CONVEYOR_POSITION
2322  Definition: Sends the conveyor position to the Kernel
2323  Opcode 147, Chapter 3.4.7, Page 3-94
2324  Return 0-OK, 1-Error, -1- not supported
2325 */
2341 DLLAPI long ER_STDCALL erSET_CONVEYOR_POSITION(ER_HND er_hnd, long input_format, long conveyor_flags, double conveyor_pos);
2342 
2343 /*erDEFINE_EVENT
2344  Definition: Defines an internal asynchronous event that is to be generated relative to position and/or time in the Kernel
2345  Opcode 148, Chapter 3.4.8, Page 3-96
2346  Return 0-OK, 1-Error, -1- not supported
2347 */
2361 DLLAPI long ER_STDCALL erDEFINE_EVENT(ER_HND er_hnd, long event_id, long target_id, double resolution, long type_of_event, double event_spec);
2362 
2363 /*erCANCEL_EVENT
2364  Definition: This function makes it possible to cancel an event previously defined in the Kernel by the erDEFINE_EVENT() function
2365  Opcode 149, Chapter 3.4.8, Page 3-99
2366  Return 0-OK, 1-Error, -1- not supported
2367 */
2377 DLLAPI long ER_STDCALL erCANCEL_EVENT(ER_HND er_hnd, long event_id);
2378 
2379 /*erGET_EVENT
2380  Definition: This function gets information about an internal asynchronous event that occurred in the Kernel
2381  Opcode 150, Chapter 3.4.8, Page 3-100
2382  Return 0-OK, 1-Error, -1- not supported
2383 */
2393 DLLAPI long ER_STDCALL erGET_EVENT(ER_HND er_hnd, long event_nr);
2394 
2395 /*erGET_MESSAGE
2396  Definition: Gives information about controller messages that occurred
2397  Opcode 154, Chapter 3.4.9, Page 3-104
2398  Return 0-OK, 1-Error, -1- not supported
2399 */
2410 DLLAPI long ER_STDCALL erGET_MESSAGE(ER_HND er_hnd, long message_number);
2411 
2412 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2413 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2414 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2415 // MotionPlanner
2416 // class ERK_CAPI_MOP_DATA
2417 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2418 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2419 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2420 
2421 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2422 // Tracking Window
2423 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2424 /* erSetTrackingWindow
2425  Aktiviert/Deaktiviert das Tracking Window und gibt den Trackingbereich [Up..Down] an.
2426  Return 0-OK, 1-Error
2427 */
2447 DLLAPI long ER_STDCALL erSetTrackingWindow(ER_HND er_hnd, long active, double up, double down, TErTrackingWindowID id_tw, char *name=NULL);
2448 
2449 /* erSetconveyorStartCondition
2450  tx0 - Offsetposition in x-Rtg. bzgl. Conveyorflanch
2451  Return 0-OK, 1-Error
2452 */
2462 DLLAPI long ER_STDCALL erSetconveyorStartCondition(ER_HND er_hnd, double tx0);
2463 
2464 //
2465 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2466 
2467 /* erSetSpeedReductionEnable
2468 */
2480 DLLAPI long ER_STDCALL erSetSpeedReductionEnable(ER_HND er_hnd,long speed_reduction_enable);
2481 
2482 /* erGetSpeedReductionEnable
2483 */
2495 DLLAPI long ER_STDCALL erGetSpeedReductionEnable(ER_HND er_hnd,long *speed_reduction_enable);
2496 
2497 /*erSELECT_MOTION_TYPE
2498  motion_type, ER_JOINT = 1, ER_LIN = 2, ER_SLEW = 3, ER_CIRC = 4
2499  Opcode 120, Chapter 3.4.4, Page 3-58
2500 */
2511 DLLAPI long ER_STDCALL erSELECT_MOTION_TYPE(ER_HND er_hnd, long motion_type);
2512 
2513 /*erSELECT_TARGET_TYPE
2514  Definition: selects one of different types for the specification of targets
2515  Opcode 121, Chapter 3.4.4, Page 3-59
2516  Return 0-OK, 1-Error
2517 
2518  Currently supported:
2519  0 - absolute w.r.t. object frame
2520  9 - single axis motion
2521 */
2533 DLLAPI long ER_STDCALL erSELECT_TARGET_TYPE(ER_HND er_hnd, long target_type);
2534 
2535 /*erSELECT_TRAJECTORY_MODE
2536  Definition: Selects on or off for the trajectory mode
2537  Opcode 122, Chapter 3.4.4, Page 3-62
2538  Return 0-OK, 1-Error, -1-not supported
2539 */
2549 DLLAPI long ER_STDCALL erSELECT_TRAJECTORY_MODE(ER_HND er_hnd, long trajectory_on);
2550 
2551 /*erSET_ADVANCE_MOTION
2552  Definition: defines the number of motions, the motion planner may run in advance of the interpolator (look_ahead)
2553  Opcode 127, Chapter 3.4.4, Page 3-67
2554 */
2562 DLLAPI long ER_STDCALL erSET_ADVANCE_MOTION(ER_HND er_hnd, long Number_of_motion);
2563 /*erSET_MOTION_FILTER
2564  Definition: defines the filter factor for smoothing velocity profiles of motions
2565  Opcode 128, Chapter 3.4.4, Page 3-68
2566 */
2575 DLLAPI long ER_STDCALL erSET_MOTION_FILTER(ER_HND er_hnd, long filter_factor);
2576 
2577 /*erREVERSE_MOTION
2578  Definition: Instructs to do a reverse motion
2579  Opcode 130, Chapter 3.4.4, Page 3-70
2580  Return 0-OK, 1-Error, -1-not supported
2581 */
2594 DLLAPI long ER_STDCALL erREVERSE_MOTION(ER_HND er_hnd, double distance );
2595 
2596 /*erSET_PAYLOAD_PARAMETER
2597  Definition: Allows specifying payloads at different locations on the robot.
2598  It has to be supported when the payload influences the motion planning.
2599  E.g. the load by a tool on the flange may be specified
2600  Opcode 160, Chapter 3.4.4, Page 3-71
2601  Return 0-OK, 1-Error, -1-not supported
2602 */
2618 DLLAPI long ER_STDCALL erSET_PAYLOAD_PARAMETER(ER_HND er_hnd, long storage, char *frame_id, long param_number, double param_value);
2619 
2620 /*erSET_CONFIGURATION_CONTROL
2621  Definition: Allows the setting of controller-specific data for the control of robot configurations
2622  Opcode 161, Chapter 3.4.4, Page 3-72
2623  Return 0-OK, 1-Error, -1-not supported
2624 */
2636 DLLAPI long ER_STDCALL erSET_CONFIGURATION_CONTROL(ER_HND er_hnd, char *param_id, char *param_contents);
2637 
2638 /*erSET_OVERRIDE_SPEED
2639  Definition: Sets correction values for scaling the programmed speed during program execution
2640  Opcode 139, Chapter 3.4.5, Page 3-82
2641  Return 0-OK, 1-Error, -1-not supported
2642 */
2656 DLLAPI long ER_STDCALL erSET_OVERRIDE_SPEED(ER_HND er_hnd, double correction_value, long correction_type);
2657 
2658 /*erSET_OVERRIDE_ACCELERATION
2659  Definition: Sets correction values for scaling the robot acceleration
2660  Opcode 155, Chapter 3.4.5, Page 3-83
2661  Return 0-OK, 1-Error, -1-not supported
2662 */
2679 DLLAPI long ER_STDCALL erSET_OVERRIDE_ACCELERATION(ER_HND er_hnd, double correction_value, long accel_type, long correction_type);
2680 
2681 /*erSET_OVERRIDE_SPEED_EX
2682  Definition: Sets override for scaling the programmed speed during program execution
2683  Return 0-OK, 1-Error, -1-not supported
2684 */
2698 DLLAPI long ER_STDCALL erSET_OVERRIDE_SPEED_EX(ER_HND er_hnd, ER_HND er_hnd_slave, double speed_override, double tcp_speed_max=0);
2699 
2700 /*erSET_OVERRIDE_ACCELERATION_EX
2701  Definition: Sets override for scaling the programmed acceleration during program execution
2702  Return 0-OK, 1-Error, -1-not supported
2703 */
2717 DLLAPI long ER_STDCALL erSET_OVERRIDE_ACCELERATION_EX(ER_HND er_hnd, ER_HND er_hnd_slave, double accel_override, double tcp_accel_max=0);
2718 
2719 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2720 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2721 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2722 // MotionPlanner
2723 // class ERK_CAPI_MOP_PATH
2724 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2725 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2726 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2727 
2728 /* erSetAutoAccel
2729  Enables automatic calculation of acceleration
2730  depending on programmed speed
2731  ON = 7 – Calculation for PTP, POS and ORI
2732  POS = 1 – Calculation for motions for Position
2733  ORI = 2 – Calculation for motions for Orientation
2734  AX = 4 – Calculation for PTP motions
2735  OFF = 0 – Calculation deactivated
2736 */
2753 DLLAPI long ER_STDCALL erSetAutoAccel(ER_HND er_hnd,long autoaccel);
2754 
2755 /* erGetAutoAccel
2756  Get status for automatic calculation of acceleration
2757  depending on programmed speed
2758  ON = 7 – Calculation for PTP, POS and ORI
2759  POS = 1 – Calculation for motions for Position
2760  ORI = 2 – Calculation for motions for Orientation
2761  AX = 4 – Calculation for PTP motions
2762  OFF = 0 – Calculation deactivated
2763 */
2780 DLLAPI long ER_STDCALL erGetAutoAccel(ER_HND er_hnd,long *autoaccel);
2781 
2782 /* erSetAccSet
2783  Set lagging of accelerations.
2784  The arguments Acc and Ramp are given in percentage values in the range 20% to 100%
2785  Acc: Acceleration and Deceleration as percentage value of normal values
2786  Ramp: Change of Acceleration and Deceleration as percentage value of normal values
2787 */
2799 DLLAPI long ER_STDCALL erSetAccSet(ER_HND er_hnd,double acc,double ramp);
2800 
2801 /* erGetAccSet
2802  Get current lagging of accelerations.
2803  The arguments Acc and Ramp are given in percentage values in the range 20% to 100%
2804  Acc: Acceleration and Deceleration as percentage value of normal values
2805  Ramp: Change of Acceleration and Deceleration as percentage value of normal values
2806 */
2818 DLLAPI long ER_STDCALL erGetAccSet(ER_HND er_hnd,double *acc,double *ramp);
2819 
2820 /* erSET_INTERPOLATION_TIME
2821  sets the interpolation time in [ms]
2822  Opcode 119, Chapter 3.4.3, Page 3-56
2823  Return 0-OK, 1-Error
2824 */
2834 DLLAPI long ER_STDCALL erSET_INTERPOLATION_TIME(ER_HND er_hnd, double InterpolationTime);
2835 
2836 
2837 /*erSELECT_ORIENTATION_INTERPOLATION_MODE
2838 NEW_041112
2839 */
2850 DLLAPI long ER_STDCALL erSELECT_ORIENTATION_INTERPOLATION_MODE(ER_HND er_hnd, long interpolation_mode, long ori_const);
2851 
2852 /*erSELECT_CIRCULAR_ORIENTATION_INTERPOLATION_MODE
2853 NEW_070122
2854  Definition:
2855  selects the circular orientation interpolation mode
2856  circ_orientation_interpolation_mode:
2857  0: use Start- and Target Orientation
2858  1: use Start-, Via- and Target Orientation, default
2859  2: use Start-, Via- and Target Orientation, hereby the robot reaches the orientation in Via Point
2860  3: Tangential in Abhängigkeit der Orientierung im StartPunkt
2861  4: Constant, Fix
2862  Return 0-OK, 1-Error
2863 */
2873 DLLAPI long ER_STDCALL erSELECT_CIRCULAR_ORIENTATION_INTERPOLATION_MODE(ER_HND er_hnd, long circ_orientation_interpolation_mode);
2874 
2875 /*erSELECT_DOMINANT_INTERPOLATION
2876  Definition: Sets the interplation space defining the movement
2877  Opcode 124, Chapter 3.4.4, Page 3-66
2878  Return 0-OK, 1-Error
2879 */
2895 DLLAPI long ER_STDCALL erSELECT_DOMINANT_INTERPOLATION(ER_HND er_hnd, long dominant_int_type, long dominant_int_param=0);
2896 
2897 /*erSET_JOINT_SPEEDS
2898  Definition:
2899  sets the joint speed expressed as percentage of the maximal joint speed for each specified joint
2900  Opcode 131, Chapter 3.4.5, Page 3-74
2901 */
2915 DLLAPI long ER_STDCALL erSET_JOINT_SPEEDS(ER_HND er_hnd, long all_joint_flags, long joint_flags, double speed_percent);
2916 
2917 /*erSET_CARTESIAN_POSITION_SPEED
2918  Definition: speed for cartesian motion [m/sec]
2919  Opcode 133, Chapter 3.4.5, Page 3-75
2920  Return 0-OK, 1-Error
2921 */
2929 DLLAPI long ER_STDCALL erSET_CARTESIAN_POSITION_SPEED(ER_HND er_hnd, double speed_value);
2930 
2931 /*erSET_CARTESIAN_ORIENTATION_SPEED
2932  Definition: sets speed for the orientation during cartesian motion [rad/sec]
2933  Opcode 134, Chapter 3.4.5, Page 3-76
2934  Return 0-OK, 1-Error
2935 */
2945 DLLAPI long ER_STDCALL erSET_CARTESIAN_ORIENTATION_SPEED(ER_HND er_hnd, long rotation_no, double speed_ori_value);
2946 
2947 /*erSET_JOINT_ACCELERATIONS
2948  sets the joint accelerations expressed as percentage of the maximal joint acceleration for each specified joint
2949  Opcode 135, Chapter 3.4.5, Page 3-77
2950  Return 0-OK, 1-Error
2951 */
2968 DLLAPI long ER_STDCALL erSET_JOINT_ACCELERATIONS(ER_HND er_hnd, long all_joint_flags, long joint_flags, double accel_percent, long accel_type);
2969 
2970 /*erSET_CARTESIAN_POSITION_ACCELERATIONS
2971  Definition: sets acceleration for cartesian motion [m/sec^2]
2972  Opcode 137, Chapter 3.4.5, Page 3-78
2973  accel_type
2974  1: // accel
2975  2: // decel
2976  3: // accel + decel
2977 */
2988 DLLAPI long ER_STDCALL erSET_CARTESIAN_POSITION_ACCELERATION(ER_HND er_hnd, double accel_value, long accel_type);
2989 
2990 /*erSET_CARTESIAN_ORIENTATION_ACCELERATION
2991  Definition: sets the acceleration for the orientation during cartesian motion [rad/sec^2]
2992  Opcode 138, Chapter 3.4.5, Page 3-79
2993  Return 0-OK, 1-Error
2994 */
3007 DLLAPI long ER_STDCALL erSET_CARTESIAN_ORIENTATION_ACCELERATION(ER_HND er_hnd, long rotation_no, double accel_ori_value, long accel_type);
3008 
3009 /*erGET_CARTESIAN_POSITION_ACCELERATIONS
3010  Definition: gets acceleration for cartesian motion [m/sec^2]
3011  accel_type
3012  1: // accel
3013  2: // decel
3014  Return 0-OK, 1-Error
3015 */
3025 DLLAPI long ER_STDCALL erGET_CARTESIAN_POSITION_ACCELERATION(ER_HND er_hnd, double *accel_value, long accel_type);
3026 
3027 /*erGET_CARTESIAN_ORIENTATION_ACCELERATION
3028  Definition: Gets the acceleration for the orientation during cartesian motion [rad/sec^2]
3029  accel_type
3030  1: // accel
3031  2: // decel
3032  Return 0-OK, 1-Error
3033 */
3045 DLLAPI long ER_STDCALL erGET_CARTESIAN_ORIENTATION_ACCELERATION(ER_HND er_hnd, long rotation_no, double *accel_ori_value, long accel_type);
3046 
3047 /*erSET_JOINT_JERKS
3048  Definition: Sets the joint jerk expressed as a percentage of the maximal joint jerk for each specified joint.
3049  Opcode 162, Chapter 3.4.5, Page 3-80
3050  Return 0-OK, 1-Error, -1-not supported
3051 */
3068 DLLAPI long ER_STDCALL erSET_JOINT_JERKS(ER_HND er_hnd, long all_joint_flags, long joint_flags, double jerk_percent, long jerk_type);
3069 
3070 /*erSET_MOTION_TIME
3071  Definition: Specifies the motion time for the next motion
3072  Opcode 156, Chapter 3.4.5, Page 3-81
3073  Return 0-OK, 1-Error, -1-not supported
3074 */
3083 DLLAPI long ER_STDCALL erSET_MOTION_TIME(ER_HND er_hnd, double time_value);
3084 
3085 
3086 /*erSELECT_FLYBY_MODE
3087 */
3098 DLLAPI long ER_STDCALL erSELECT_FLYBY_MODE(ER_HND er_hnd, long flyby_on);
3099 
3100 /*erSET_FLYBY_CRITERIA_PARAMETER
3101  Definition: Sets the value of a flyby parameter
3102  Opcode 141, Chapter 3.4.6, Page 3-86
3103  Return 0-OK, 1-Error, -1- not supported
3104 */
3116 DLLAPI long ER_STDCALL erSET_FLYBY_CRITERIA_PARAMETER(ER_HND er_hnd, long param_number, long joint_nr, double param_value);
3117 
3118 /*erSELECT_FLYBY_CRITERIA
3119  Definition: Selects a flyby criterion (parameter)
3120  Opcode 142, Chapter 3.4.6, Page 3-87
3121  Return 0-OK, 1-Error, -1- not supported
3122 */
3132 DLLAPI long ER_STDCALL erSELECT_FLYBY_CRITERIA(ER_HND er_hnd, long param_number);
3133 
3134 /*erCANCEL_FLYBY_CRITERIA
3135  Definition: Cancels (unselects) a fly-by criterion
3136  Opcode 143, Chapter 3.4.6, Page 3-88
3137  Return 0-OK, 1-Error, -1- not supported
3138 */
3148 DLLAPI long ER_STDCALL erCANCEL_FLYBY_CRITERIA(ER_HND er_hnd, long param_number);
3149 
3150 /*erSELECT_POINT_ACCURACY
3151  Definition: Selects a criterion for when a target is reached
3152  Opcode 144, Chapter 3.4.6, Page 3-89
3153  Return 0-OK, 1-Error, -1- not supported
3154 */
3164 DLLAPI long ER_STDCALL erSELECT_POINT_ACCURACY(ER_HND er_hnd, long accuracy_type);
3165 
3166 /*erSET_POINT_ACCURACY_PARAMETER
3167  Definition: Sets the value of a parameter determining point accuracy
3168  Opcode 145, Chapter 3.4.6, Page 3-90
3169  Return 0-OK, 1-Error, -1- not supported
3170 */
3181 DLLAPI long ER_STDCALL erSET_POINT_ACCURACY_PARAMETER(ER_HND er_hnd, long accuracy_type, double accuracy_value );
3182 
3183 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3184 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3185 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3186 // MotionPlanner
3187 // class ERK_CAPI_MOP_PREP
3188 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3189 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3190 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3191 
3192 /* erSET_NEXT_TARGET
3193  sends the next target position. This may include intermediate position, radius, angle for circular motion
3194  Opcode 117, Chapter 3.4.3, Page 3-52
3195  Return
3196  1 - need more data, nothing to do
3197  0 - OK, next step is calculated successful
3198  -17 - specified motion type is not supported
3199  -34 - Error in matrix. Incomplete matrix
3200  -35 - Cartesian position expected
3201  -36 - Joint position expected
3202  -43 - Initial position not set
3203  -51 - no solution is found. One joint is out of range
3204  -52 - Cartesian position is out of work range
3205  -59 - specified position is singular
3206  -68 - fatal error, stopped calculating
3207  -71 - Position not stored, target buffer is full
3208  -78 - The specified position is not acceptable
3209  -79 - Not ready to receive targets
3210 */
3237 DLLAPI long ER_STDCALL erSET_NEXT_TARGET(ER_HND er_hnd, NEXT_TARGET_DATA *p_next_target_data);
3238 
3239 /* erSET_NEXT_TARGET_ADVANCE
3240  Definition: Sends about next target data
3241  Return 0-OK, 1-Error
3242 */
3253 DLLAPI long ER_STDCALL erSET_NEXT_TARGET_ADVANCE(ER_HND er_hnd, NEXT_TARGET_DATA_ADVANCE *p_next_target_data_advance);
3254 
3255 /*erSTOP_MOTION
3256  Definition: Stops the on-going motion toward the target
3257  Opcode 151, Chapter 3.4.8, Page 3-101
3258  Return 0-OK, 1-Error
3259 */
3271 DLLAPI long ER_STDCALL erSTOP_MOTION(ER_HND er_hnd);
3272 
3273 /*erCONTINUE_MOTION
3274  Definition: Continues a motion that was stopped with the erSTOP_MOTION() function
3275  Opcode 152, Chapter 3.4.8, Page 3-102
3276  Return 0-OK, 1-Error
3277 */
3289 
3290 /*erCANCEL_MOTION
3291  Definition: Cancel a motion that was stopped with erSTOP_MOTION() function
3292  Opcode 153, Chapter 3.4.8, Page 3-103
3293  Return 0-OK, 1-Error
3294 */
3306 
3307 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3308 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3309 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3310 // MotionPlanner
3311 // class ERK_CAPI_MOP_EXEC
3312 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3313 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3314 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3315 
3316 /* erGET_NEXT_STEP
3317  returns the next interpolated position step, the
3318  elapsed time and supplementary information like events, joint limits and messages
3319  Opcode 118, Chapter 3.4.3, Page 3-54
3320  Return
3321  2 - final step, target reached or speed is zero
3322  1 - need more data, nothing to do
3323  0 - OK, next step is calculated successful
3324  -13 - the specified output format is not supported
3325  -17 - the specified motion type is not supported
3326  -25 - the motion is not possible in the specified time
3327  -42 - no target set
3328  -51 - no solution is found. One joint is out of range
3329  -52 - Cartesian position is out of work range
3330  -68 - fatal error, stopped calculating
3331  -76 - incomplete or inconsistent motion specification, can't move
3332  -1053 - Cartesian position is out of boudary work range
3333  -1059 - Cartesian position is singular
3334 */
3366 DLLAPI long ER_STDCALL erGET_NEXT_STEP(ER_HND er_hnd, long output_format, NEXT_STEP_DATA *p_next_step_data, double time);
3367 
3377 DLLAPI long ER_STDCALL erGetCurrentStepData(ER_HND er_hnd, CURRENT_STEP_DATA *p_current_step_data);
3378 
3379 /*erSET_OVERRIDE_POSITION
3380  Definition: Sets a correction offset which will be added to the path during program execution
3381  This function can be used for sensor-compensated motion. It is effective at each time step. The passed value is valid until the function is called again.
3382  Opcode 129, Chapter 3.4.4, Page 3-69
3383  Return 0-OK, 1-Error, -1- not supported
3384 */
3394 DLLAPI long ER_STDCALL erSET_OVERRIDE_POSITION(ER_HND er_hnd, DFRAME *PosOffset);
3395 
3396 /*erGET_CURRENT_TARGETID
3397  Definition: Returns the TargetID of the motion in execution
3398  Opcode 163, Chapter 3.4.6, Page 3-91
3399  Return 0-OK, 1-Error
3400 */
3409 
3410 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3411 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3412 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3413 // ToolPath
3414 // class ERK_CAPI_TOOLPATH
3415 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3416 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3417 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3443 DLLAPI long ER_STDCALL erInitToolPath (ER_HND er_hnd, ER_TOOLPATH_HND *er_tpth_hnd);
3444 
3451 
3462 DLLAPI long ER_STDCALL erInsertToolPath (ER_HND er_hnd, ER_TOOLPATH_HND *er_tpth_hnd, ER_TOOLPATH_HND er_tpth_hnd_ref);
3463 
3471 DLLAPI long ER_STDCALL erSwapToolPath (ER_TOOLPATH_HND er_tpth_hnd1, ER_TOOLPATH_HND er_tpth_hnd2);
3472 
3478 DLLAPI long ER_STDCALL erToolPathGetTargetLocationNumber (ER_TOOLPATH_HND er_tpth_hnd); // Number of Targets in ToolPath
3479 
3480 //DLLAPI ER_HND ER_STDCALL erToolPathGetER_HND (ER_TOOLPATH_HND er_tpth_hnd); // Device Handle belonging to tool path handle
3481 
3487 //static DLLAPI ER_HND ER_STDCALL erToolPathGetER_HND (ER_TOOLPATH_HND er_tpth_hnd); // Device Handle belonging to tool path handle
3488 
3493 DLLAPI char* ER_STDCALL erToolPathName (ER_TOOLPATH_HND er_tpth_hnd); // Name ToolPath
3494 
3501 DLLAPI long ER_STDCALL erToolPathEnable (ER_TOOLPATH_HND er_tpth_hnd, long enable); // 0-Disable, 1-Enable, 2-Status
3502 
3508 DLLAPI ER_HND ER_STDCALL erToolPathGetRobotHandle (ER_TOOLPATH_HND er_tpth_hnd); // Get Robot Handle belonging to tool path handle
3509 
3515 DLLAPI ER_HND ER_STDCALL erToolPathGetTrackMotionHandle (ER_TOOLPATH_HND er_tpth_hnd); // Get TrackMotion Handle belonging to tool path handle
3516 
3522 DLLAPI ER_HND ER_STDCALL erToolPathGetPositionerHandle (ER_TOOLPATH_HND er_tpth_hnd); // Get Positioner Handle belonging to tool path handle
3523 
3529 DLLAPI ER_HND ER_STDCALL erToolPathGetConveyorHandle (ER_TOOLPATH_HND er_tpth_hnd); // Get Conveyor Handle belonging to tool path handle
3530 
3539 DLLAPI long ER_STDCALL erToolPathSetTrackMotionHandle (ER_TOOLPATH_HND er_tpth_hnd, ER_HND hnd_TrackMotion=NULL); // Set TrackMotion Handle belonging to tool path handle
3548 DLLAPI long ER_STDCALL erToolPathSetPositionerHandle (ER_TOOLPATH_HND er_tpth_hnd, ER_HND hnd_Positioner=NULL); // Set Positioner Handle belonging to tool path handle
3557 DLLAPI long ER_STDCALL erToolPathSetConveyorHandle (ER_TOOLPATH_HND er_tpth_hnd, ER_HND hnd_Conveyor=NULL); // Set Conveyor Handle belonging to tool path handle
3558 
3563 DLLAPI char* ER_STDCALL erToolPathLogFileName (ER_TOOLPATH_HND er_tpth_hnd); // Log File Name ToolPath
3568 DLLAPI char* ER_STDCALL erToolPathPrgFileName (ER_TOOLPATH_HND er_tpth_hnd); // Prg File Name ToolPath
3569 
3575 
3581 
3589 DLLAPI long ER_STDCALL CpyMotionAttributesTemplate (ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_ATTRIBUTES_HND hnd); // Copy target attributes data to template
3590 
3598 
3607 
3615 
3624 
3632 
3641 
3649 
3658 
3666 
3675 
3683 
3684 
3691 DLLAPI long ER_STDCALL erToolPathReset (ER_TOOLPATH_HND er_tpth_hnd); // Reset all tool path target locations
3692 
3701 DLLAPI long ER_STDCALL erToolPathResetInitRobot(ER_TOOLPATH_HND er_tpth_hnd, double *q_start=NULL); // Read current joint data from loaded robot, set initial joint start location
3702 
3711 DLLAPI long ER_STDCALL erToolPathResetInitTrackMotion(ER_TOOLPATH_HND er_tpth_hnd, double *q_start=NULL); // Read current joint data from loaded TrackMotion, set initial joint start location
3712 
3721 DLLAPI long ER_STDCALL erToolPathResetInitPositioner(ER_TOOLPATH_HND er_tpth_hnd, double *q_start=NULL); // Read current joint data from loaded Positioner, set initial joint start location
3722 
3731 DLLAPI long ER_STDCALL erToolPathResetInitConveyor(ER_TOOLPATH_HND er_tpth_hnd, double *q_start=NULL); // Read current joint data from loaded Conveyor, set initial joint start location
3732 
3741 DLLAPI long ER_STDCALL erToolPathSetInitPos(ER_TOOLPATH_HND er_tpth_hnd, double InterpolationTime=0); // Initializes the MotionPlanner based on current settings
3742 
3743 //DLLAPI long ER_STDCALL erToolPathRunAdv (ER_TOOLPATH_HND er_tpth_hnd);
3744 
3798 
3901 DLLAPI long ER_STDCALL erGET_NEXT_TOOLPATH_STEP(ER_TOOLPATH_HND er_tpth_hnd, long cntrl, NEXT_STEP_DATA *p_next_step_data=NULL, double time=0);
3902 
3909 
3918 
3919 //DLLAPI long ER_STDCALL erToolPathDefinition (ER_TOOLPATH_HND er_tpth_hnd); // erzeugt einige TargetLocations
3920 
3921 //--------------------------------
3922 // Target Location ... ERK_CAPI_TOOLPATH_TARGETS
3923 //--------------------------------
3924 // Target Locations
3933 DLLAPI long ER_STDCALL erTargetLocationReset (ER_TARGET_LOCATION_HND er_tarloc_hnd); // Reset target location
3934 
3957 DLLAPI long ER_STDCALL erInsertTargetLocation (ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_LOCATION_HND *er_tarloc_hnd, ER_TARGET_LOCATION_HND er_tarloc_hnd_ref=NULL);
3976 
3981 DLLAPI long ER_STDCALL erGetTargetLocationNumber (ER_TARGET_LOCATION_HND er_tarloc_hnd); // Number of Targets in ToolPath
3986 DLLAPI ER_HND ER_STDCALL erhGetTargetLocationER_HND (ER_TARGET_LOCATION_HND er_tarloc_hnd); // Device Handle belonging to target location handle
3987 
4012 
4025 DLLAPI long ER_STDCALL erSetTargetLocation_Move_JointAbs (ER_TARGET_LOCATION_HND er_tarloc_hnd,double *JointPos,double speed_percent=0, double override_speed=0, double *Tool=0);
4041 DLLAPI long ER_STDCALL erSetTargetLocation_Move_Joint (ER_TARGET_LOCATION_HND er_tarloc_hnd, double *CartPosVec, long configuration=0, long ptp_target_calculation_mode=ER_PTP_TARGET_CALC_MODE_UNDEF, double speed_percent=0, double override_speed=0, double *Tool=0, double *Base=0);
4054 DLLAPI long ER_STDCALL erSetTargetLocation_Move_SlewAbs (ER_TARGET_LOCATION_HND er_tarloc_hnd,double *JointPos,double speed_percent=0, double override_speed=0, double *Tool=0);
4070 DLLAPI long ER_STDCALL erSetTargetLocation_Move_Slew (ER_TARGET_LOCATION_HND er_tarloc_hnd, double *CartPosVec, long configuration=0, long ptp_target_calculation_mode=ER_PTP_TARGET_CALC_MODE_UNDEF, double speed_percent=0, double override_speed=0, double *Tool=0, double *Base=0);
4086 DLLAPI long ER_STDCALL erSetTargetLocation_Move_LIN (ER_TARGET_LOCATION_HND er_tarloc_hnd, double *CartPosVec, double speed_cp=0, double speed_ori=0, double override_speed=0, long flyby_on=-1, double *Tool=0, double *Base=0);
4103 DLLAPI long ER_STDCALL erSetTargetLocation_Move_CIRC (ER_TARGET_LOCATION_HND er_tarloc_hnd, double *CartPosVecVia, double *CartPosVec, double speed_cp=0, double speed_ori=0, double override_speed=0, long flyby_on=-1, double *Tool=0, double *Base=0);
4104 //DLLAPI long ER_STDCALL erSetTargetLocation_ExtAx_TrackMotion (ER_TARGET_LOCATION_HND er_tarloc_hnd, double axis_value_01, double speed_value_01=0, long sync_type=ER_SYNC_UNDEF, ER_HND er_hnd_connect=0);
4105 //DLLAPI long ER_STDCALL erSetTargetLocation_ExtAx_Positioner (ER_TARGET_LOCATION_HND er_tarloc_hnd, double axis_value_01,double axis_value_02, double speed_value_01=0, double speed_value_02=0, long sync_type=ER_SYNC_UNDEF, ER_HND er_hnd_connect=0);
4106 
4107 //--------------------------------
4108 // Header Data ... TARGET_HEAD, ERK_CAPI_TOOLPATH_HEAD
4109 //--------------------------------
4110  // Header Data
4151 DLLAPI long ER_STDCALL erTargetLocationValid (ER_TARGET_LOCATION_HND er_tarloc_hnd, long valid); // 0-Disable, 1-Enable, 2-Status
4152 
4153 //------------------------------------------------------------------------------
4154 // Instructions, individual information text ... TARGET_INSTRUCTIONS
4155 //------------------------------------------------------------------------------
4171 DLLAPI char *ER_STDCALL erGetInstructions_information (ER_TARGET_LOCATION_HND er_tarloc_hnd); // User defined individual information text
4178 DLLAPI char *ER_STDCALL erGetInstructions_LeadInstructions (ER_TARGET_LOCATION_HND er_tarloc_hnd); // Instructions separated by semicolon, when target is reached
4185 DLLAPI char *ER_STDCALL erGetInstructions_LagInstructions (ER_TARGET_LOCATION_HND er_tarloc_hnd); // Instructions separated by semicolon, before move will start
4195 DLLAPI int ER_STDCALL erSetInstructions (ER_TARGET_LOCATION_HND er_tarloc_hnd, char *InfoTxt=NULL, char *LeadInst=NULL, char *LagInst=NULL); // Set Instructions: information text, LeadInstructions, LagInstructions
4196 
4197 //--------------------------------
4198 // Auxiliary Motion Attributes ... TARGET_ATTRIBUTES_AUX
4199 //--------------------------------
4200  // Auxiliary Motion Attributes
4207 
4208 //--------------------------------
4209 // Motion Attributes ... TARGET_ATTRIBUTES
4210 //--------------------------------
4211  // Motion Attributes
4228 DLLAPI long *ER_STDCALL erGetMotionAttributes_enabled (ER_TARGET_ATTRIBUTES_HND hnd); // enables/disables this target
4234 DLLAPI TErTargetID *ER_STDCALL erGetMotionAttributes_target_id (ER_TARGET_ATTRIBUTES_HND hnd); // unique target ID, NEXT_TARGET_DATA.TargetID
4242 DLLAPI double *ER_STDCALL erGetMotionAttributes_WobjCartPosVec (ER_TARGET_ATTRIBUTES_HND hnd); // WorkObject valid for all cartesian targets CartPosVec, CartPosVecVia
4249 DLLAPI long *ER_STDCALL erGetMotionAttributes_ext_tcp_mode (ER_TARGET_ATTRIBUTES_HND hnd); // The external TCP can be ::IPO_MODE_BASE (tool guided) or ::IPO_MODE_TOOL (work object guided), erSetExtTcpMode()
4258 DLLAPI double *ER_STDCALL erGetMotionAttributes_BaseVec (ER_TARGET_ATTRIBUTES_HND hnd); // work object, $BASE, $UFrame has only effect if ::IPO_MODE_BASE, erSetBaseRobotBase()
4266 DLLAPI long *ER_STDCALL erGetMotionAttributes_BaseIdx (ER_TARGET_ATTRIBUTES_HND hnd); // user defined Idx for work object, $BASE, $UFrame has only effect if ::IPO_MODE_BASE, erSetBaseRobotBase()
4274 DLLAPI char *ER_STDCALL erGetMotionAttributes_BaseName (ER_TARGET_ATTRIBUTES_HND hnd); // user defined Name for work object, $BASE, $UFrame has only effect if ::IPO_MODE_BASE, erSetBaseRobotBase()
4275 
4276 
4301 
4302 
4327 
4328 
4353 
4354 
4362 DLLAPI double *ER_STDCALL erGetMotionAttributes_ToolVec (ER_TARGET_ATTRIBUTES_HND hnd); // Tool/TCP data, erSetTool()
4370 DLLAPI long *ER_STDCALL erGetMotionAttributes_ToolIdx (ER_TARGET_ATTRIBUTES_HND hnd); // user defined Idx for Tool/TCP data, erSetTool()
4378 DLLAPI char *ER_STDCALL erGetMotionAttributes_ToolName (ER_TARGET_ATTRIBUTES_HND hnd); // user defined Name for Tool/TCP data, erSetTool()
4379 
4387 DLLAPI double *ER_STDCALL erGetMotionAttributes_ToolOffsetVec(ER_TARGET_ATTRIBUTES_HND hnd); // Tool/TCP offset data, erSetToolOffset()
4395 DLLAPI long *ER_STDCALL erGetMotionAttributes_ToolOffsetIdx(ER_TARGET_ATTRIBUTES_HND hnd); // user defined Idx for Tool/TCP offset data, erSetToolOffset()
4403 DLLAPI char *ER_STDCALL erGetMotionAttributes_ToolOffsetName(ER_TARGET_ATTRIBUTES_HND hnd); // user defined Name for Tool/TCP offset data, erSetToolOffset()
4404 
4422 DLLAPI long *ER_STDCALL erGetMotionAttributes_motype (ER_TARGET_ATTRIBUTES_HND hnd); // ER_JOINT , ER_LIN, ER_SLEW, ER_CIRC, erSELECT_MOTION_TYPE()
4432 DLLAPI long *ER_STDCALL erGetMotionAttributes_dom_type (ER_TARGET_ATTRIBUTES_HND hnd); // 1-ER_DOMINANT_INTERPOLATION_POS, 2-ER_DOMINANT_INTERPOLATION_ORI, 3-ER_DOMINANT_INTERPOLATION_AXIS, 4-ER_DOMINANT_INTERPOLATION_AUTO, erSELECT_DOMINANT_INTERPOLATION()
4440 DLLAPI long *ER_STDCALL erGetMotionAttributes_advance_motion (ER_TARGET_ATTRIBUTES_HND hnd); // look ahead by 1 is only supported, erSET_ADVANCE_MOTION()
4448 DLLAPI double *ER_STDCALL erGetMotionAttributes_override_speed (ER_TARGET_ATTRIBUTES_HND hnd); // [%] Sets correction values for scaling the programmed speed, becomes effective for the next target supplied by erSET_NEXT_TARGET, erSET_OVERRIDE_SPEED()
4457 DLLAPI double *ER_STDCALL erGetMotionAttributes_acc (ER_TARGET_ATTRIBUTES_HND hnd); // 20-100[%] Set lagging of accelerations deceleration, erSetAccSet()
4466 DLLAPI double *ER_STDCALL erGetMotionAttributes_ramp (ER_TARGET_ATTRIBUTES_HND hnd); // 20-100[%] Set lagging of accelerations deceleration, erSetAccSet()
4476 DLLAPI long *ER_STDCALL erGetMotionAttributes_filter_factor (ER_TARGET_ATTRIBUTES_HND hnd); // Velocity profile: 0-geo (ER_MOTION_FILTER_GEO), 1-c2 (ER_MOTION_FILTER_C2), erSET_MOTION_FILTER()
4486 DLLAPI long *ER_STDCALL erGetMotionAttributes_flyby_on (ER_TARGET_ATTRIBUTES_HND hnd); // 0-OFF, 1-ON only when LIN or CIRC, erSELECT_FLYBY_MODE()
4496 DLLAPI double *ER_STDCALL erGetMotionAttributes_flyby_speed_percent (ER_TARGET_ATTRIBUTES_HND hnd); // if flyby_on enabled: [%], erSET_FLYBY_CRITERIA_PARAMETER(), tbd
4506 DLLAPI double *ER_STDCALL erGetMotionAttributes_flyby_dist (ER_TARGET_ATTRIBUTES_HND hnd); // if flyby_on enabled: [m], erSET_FLYBY_CRITERIA_PARAMETER(), tbd
4522 DLLAPI long *ER_STDCALL erGetMotionAttributes_autoaccel (ER_TARGET_ATTRIBUTES_HND hnd); // ER_AUTOACCEL_MODE_OFF, -_POS, -_ORI, -_AX, -_DEF, -_ON, erSetAutoAccel()
4531 DLLAPI double *ER_STDCALL erGetMotionAttributes_LeadWaitTime (ER_TARGET_ATTRIBUTES_HND hnd); // Wait time [s], before move will start, NEXT_TARGET_DATA.LeadWaitTime
4540 DLLAPI double *ER_STDCALL erGetMotionAttributes_LagWaitTime (ER_TARGET_ATTRIBUTES_HND hnd); // Wait time [s], after robot reaches its target, NEXT_TARGET_DATA.LagWaitTime
4541 
4542 //--------------------------------
4543 // Target data for Joint Move ... ERK_CAPI_TOOLPATH_MOVE_JOINT
4544 //--------------------------------
4564 DLLAPI long *ER_STDCALL erGetMoveJoint_target_type (ER_TARGET_MOVE_JOINT_HND hnd); // ER_TARGET_TYPE_ABS, ER_TARGET_TYPE_ABSJOINT, erSELECT_TARGET_TYPE()
4570 DLLAPI double *ER_STDCALL erGetMoveJoint_speed_percent (ER_TARGET_MOVE_JOINT_HND hnd); // joint speed [%], erSET_JOINT_SPEEDS()
4576 DLLAPI double *ER_STDCALL erGetMoveJoint_accel_percent (ER_TARGET_MOVE_JOINT_HND hnd); // joint acceleration [%], erSET_JOINT_ACCELERATIONS()
4586 DLLAPI double *ER_STDCALL erGetMoveJoint_JointPos (ER_TARGET_MOVE_JOINT_HND hnd); // Target Joint Location for ER_TARGET_TYPE_ABSJOINT, q1 [m,rad], NEXT_TARGET_DATA.JointPos
4597 DLLAPI double *ER_STDCALL erGetMoveJoint_CartPosVec (ER_TARGET_MOVE_JOINT_HND hnd); // Cart. Target Location for ER_TARGET_TYPE_ABS, Pxyz [m] Rxyz [rad], NEXT_TARGET_DATA.CartPos
4603 DLLAPI long *ER_STDCALL erGetMoveJoint_configuration (ER_TARGET_MOVE_JOINT_HND hnd); // Target manipulator configuration string, NEXT_TARGET_DATA.Configuration
4611 DLLAPI long *ER_STDCALL erGetMoveJoint_ptp_target_calculation_mode (ER_TARGET_MOVE_JOINT_HND hnd); // PTP target calculation mode, ::ER_PTP_TARGET_CALC_MODE_SHORTEST_ANGLE, ::ER_PTP_TARGET_CALC_MODE_TURNS, ::ER_PTP_TARGET_CALC_MODE_MATH, ::ER_PTP_TARGET_CALC_MODE_IN_TRAVEL_RANGE, ::ER_PTP_TARGET_CALC_MODE_VAR_CONFIG, NEXT_TARGET_DATA.ptp_target_calculation_mode
4619 DLLAPI long *ER_STDCALL erGetMoveJoint_turn_value (ER_TARGET_MOVE_JOINT_HND hnd); // Target turn values if ::ER_PTP_TARGET_CALC_MODE_TURNS is enabled, NEXT_TARGET_DATA.turn_value[]
4620 
4621 //--------------------------------
4622 // Target data for CP Move ... ERK_CAPI_TOOLPATH_MOVE_CP
4623 //--------------------------------
4642 DLLAPI long *ER_STDCALL erGetMoveCP_target_type (ER_TARGET_MOVE_CP_HND hnd); // ER_TARGET_TYPE_ABS
4648 DLLAPI double *ER_STDCALL erGetMoveCP_speed_cp (ER_TARGET_MOVE_CP_HND hnd); // cp speed [m/s], ori speed [deg/s], erSET_CARTESIAN_POSITION_SPEED(), erSET_CARTESIAN_ORIENTATION_SPEED()
4654 DLLAPI double *ER_STDCALL erGetMoveCP_speed_ori (ER_TARGET_MOVE_CP_HND hnd); // cp speed [m/s], ori speed [deg/s], erSET_CARTESIAN_POSITION_SPEED(), erSET_CARTESIAN_ORIENTATION_SPEED()
4660 DLLAPI double *ER_STDCALL erGetMoveCP_accel_cp (ER_TARGET_MOVE_CP_HND hnd); // cp accel [m/s^2], [deg/s^2], erSET_CARTESIAN_POSITION_ACCELERATION(), erSET_CARTESIAN_ORIENTATION_ACCELERATION()
4666 DLLAPI double *ER_STDCALL erGetMoveCP_accel_ori (ER_TARGET_MOVE_CP_HND hnd); // cp accel [m/s^2], [deg/s^2], erSET_CARTESIAN_POSITION_ACCELERATION(), erSET_CARTESIAN_ORIENTATION_ACCELERATION()
4677 DLLAPI double *ER_STDCALL erGetMoveCP_CartPosVec (ER_TARGET_MOVE_CP_HND hnd); // Cart. Target Location for ER_LIN and ER_CIRC move, Pxyz [m] Rxyz [rad], NEXT_TARGET_DATA.CartPos
4687 DLLAPI double *ER_STDCALL erGetMoveCP_CartPosVecVia (ER_TARGET_MOVE_CP_HND hnd); // Cart. Via Location for ER_CIRC move, Pxyz [m] Rxyz [rad], NEXT_TARGET_DATA.CartPos
4695 DLLAPI long *ER_STDCALL erGetMoveCP_interpolation_mode (ER_TARGET_MOVE_CP_HND hnd); // =1 one angle (QUATERNION), =2 two angle (QUATERNION), =3 three angle (VARIABLE), erSELECT_ORIENTATION_INTERPOLATION_MODE()
4709 DLLAPI long *ER_STDCALL erGetMoveCP_circ_orientation_interpolation_mode (ER_TARGET_MOVE_CP_HND hnd); // ::ER_CIRC_ORI_INTERPOLATION_START_END ... ::ER_CIRC_ORI_INTERPOLATION_FIX, erSELECT_CIRCULAR_ORIENTATION_INTERPOLATION_MODE()
4710 
4711 //--------------------------------
4712 // Motion execution data at target ... ERK_CAPI_TOOLPATH_MOTION_EXEC
4713 //--------------------------------
4736 DLLAPI long ER_STDCALL erGetMotionExec_motion_success (ER_TARGET_MOTION_EXEC_HND hnd); // 1 - TARGET_LOCATION reached successfully, 0 - TARGET_LOCATION not reached successfully
4743 DLLAPI double ER_STDCALL erGetMotionExec_time_stamp (ER_TARGET_MOTION_EXEC_HND hnd); // Time stamp [s] when target location is reached
4748 DLLAPI double ER_STDCALL erGetMotionExec_trajectory_time (ER_TARGET_MOTION_EXEC_HND hnd); // Trajectory Time [s] for current motion to target
4762 DLLAPI long ER_STDCALL erGetMotionExec_configuration (ER_TARGET_MOTION_EXEC_HND hnd); // current manipulator configuration at target location, [1..number of robot configurations]
4768 DLLAPI double *ER_STDCALL erGetMotionExec_JointPos (ER_TARGET_MOTION_EXEC_HND hnd); // Joint Location at target location
4774 DLLAPI double *ER_STDCALL erGetMotionExec_ExtAxValues (ER_TARGET_MOTION_EXEC_HND hnd); // External axis values at target location
4775 
4776 //--------------------------------
4777 // External axis data definition for Track/Slider-Motion ... ERK_CAPI_TOOLPATH_EXTAX_TRACKMOTION
4778 //--------------------------------
4779  // External axis data definition for Track/Slider-Motion
4834 DLLAPI long *ER_STDCALL erGetExtAxTrack_number_extax_used (ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND hnd); // Number of "used" external axis. Note: The total number of external axis must not exceed ER_EXTAX_KIN_DATA_MAX
4842 DLLAPI long *ER_STDCALL erGetExtAxTrack_sync_type (ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND hnd); // ER_SYNC_OFF, ER_SYNC_ON, erConnectTrackMotionSetSync()
4856 DLLAPI ER_EXTAX_KIN_DATA *ER_STDCALL erGetExtAxTrack_extax_data (ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND hnd, long extax_idx); // external axis data, NEXT_TARGET_DATA.extax_data[]
4870 DLLAPI long ER_STDCALL erSetExtAxTrackIdx (ER_TARGET_LOCATION_HND er_tarloc_hnd, long extax_idx, double axis_value, double speed_value=0, long sync_type=ER_SYNC_UNDEF, ER_HND er_hnd_connect=0);
4871 
4872 //--------------------------------
4873 // External axis data definition for Positioner/TurnTable ... ERK_CAPI_TOOLPATH_EXTAX_POSITIONER
4874 //--------------------------------
4941 DLLAPI long *ER_STDCALL erGetExtAxPositioner_number_extax_used (ER_TARGET_EXTAX_DEVICE_POSITIONER_HND hnd); // Number of "used" external axis. Note: The total number of external axis must not exceed ER_EXTAX_KIN_DATA_MAX
4949 DLLAPI long *ER_STDCALL erGetExtAxPositioner_sync_type (ER_TARGET_EXTAX_DEVICE_POSITIONER_HND hnd); // ER_SYNC_OFF, ER_SYNC_ON, erConnectPositionerSetSync()
4963 DLLAPI ER_EXTAX_KIN_DATA *ER_STDCALL erGetExtAxPositioner_extax_data (ER_TARGET_EXTAX_DEVICE_POSITIONER_HND hnd, long extax_idx); // external axis data, NEXT_TARGET_DATA.extax_data[]
4977 DLLAPI long ER_STDCALL erSetExtAxPositionerIdx (ER_TARGET_LOCATION_HND er_tarloc_hnd, long extax_idx, double axis_value, double speed_value=0, long sync_type=ER_SYNC_UNDEF, ER_HND er_hnd_connect=0);
4978 
4979 //--------------------------------
4980 // External axis data definition for Conveyor ... ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND
4981 //--------------------------------
5000  DLLAPI long *ER_STDCALL erGetExtAxConveyor_number_extax_used(ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND hnd); // Number of "used" external axis. Note: The total number of external axis must not exceed ER_EXTAX_KIN_DATA_MAX
5008  DLLAPI long *ER_STDCALL erGetExtAxConveyor_sync_type(ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND hnd); // ER_SYNC_OFF, ER_SYNC_ON, erConnectConveyorSetSync()
5022  DLLAPI ER_EXTAX_KIN_DATA *ER_STDCALL erGetExtAxConveyor_extax_data(ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND hnd, long extax_idx); // external axis data, NEXT_TARGET_DATA.extax_data[]
5036  DLLAPI long ER_STDCALL erSetExtAxConveyorIdx(ER_TARGET_LOCATION_HND er_tarloc_hnd, long extax_idx, double axis_value, double speed_value = 0, long sync_type = ER_SYNC_UNDEF, ER_HND er_hnd_connect = 0);
5037 
5057  DLLAPI long ER_STDCALL erSetConveyorTrackingWindow(ER_TARGET_LOCATION_HND er_tarloc_hnd, long active, double up, double down, TErTrackingWindowID id_tw, char *name = NULL);
5058 
5069 
5070 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5071 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5072 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5073 // ToolBox
5074 // class ERK_CAPI_TOOLPATH_TOOLBOX
5075 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5076 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5077 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5088 DLLAPI long ER_STDCALL erTPth_TBox_Fct(int FctIdx, int FctSubIdx, ER_TOOLPATH_HND er_tpth_hnd, int constraint_param, char *svalues=NULL);
5089 
5090 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5091 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5092 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5093 // ToolBox
5094 // class ERK_CAPI_TOOLPATH_APIPP
5095 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5096 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5097 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5137 DLLAPI long ER_STDCALL erTPth_PostProc(char *ApiPP_Dll_Name, int FctIdx, int FctSubIdx, ER_TOOLPATH_HND er_tpth_hnd, char *program_name, char *target_path=NULL, int pp_param=0, char *svalues=NULL);
5138 
5139 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5140 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5141 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5142 // ToolPath
5143 // class ERK_CAPI_TOOLPATH_CREATE
5144 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5145 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5146 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5152 DLLAPI long ER_STDCALL erTPth_Fct(ER_TOOLPATH_HND er_tpth_hnd);
5153 
5154 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5155 // class ERK_CAPI_SIM
5156 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5157 
5158 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5159 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5160 // erColl_ - Functions
5161 // class ERK_CAPI_SIM_COLLISION
5162 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5163 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5164 
5165 /* Creates a collision handle for one Model and preallocate memory for n_tris triangles
5166 */
5175 DLLAPI long ER_STDCALL erColl_BeginModel(ER_COLLISION_HND *er_coll_hnd, long n_tris);
5176 
5177 /* Adds a triangle to a Model
5178 */
5190 DLLAPI long ER_STDCALL erColl_AddTri(ER_COLLISION_HND er_coll_hnd, double *p1, double *p2, double *p3, long id);
5191 
5192 /* Stop building a Model
5193 */
5201 
5202 /* Perform the collision check of two Models
5203 See also erColl_ChkCollision_res() to get the collision results immediately
5204 */
5358 DLLAPI long ER_STDCALL erColl_ChkCollision(ER_COLLISION_HND er_coll_hnd_1, DFRAME *iT_1,ER_COLLISION_HND er_coll_hnd_2, DFRAME *iT_2, long query_type=ER_COLL_QUERY_TYPE_COLLIDE, long contact_type=ER_COLL_FIRST_CONTACT, double rel_err=0, double abs_err=0, double tolerance=0);
5359 
5360 /* Perform the collision check of two Models
5361  Collision results returned immediately compared to erColl_ChkCollision()
5362  */
5706 DLLAPI long ER_STDCALL erColl_ChkCollision_res(ER_COLLISION_HND er_coll_hnd_1, DFRAME *iT_1,ER_COLLISION_HND er_coll_hnd_2, DFRAME *iT_2, long query_type=ER_COLL_QUERY_TYPE_COLLIDE, long contact_type=ER_COLL_FIRST_CONTACT, double rel_err=0, double abs_err=0, double tolerance=0, void *pres=NULL);
5707 
5739 DLLAPI long ER_STDCALL erColl_ChkCollision_res_free(long query_type, void *pres);
5740 
5741 /* Unload a Model. Free all allocated memory
5742 */
5750 
5751 /* Get Collision result for query ::ER_COLL_QUERY_TYPE_COLLIDE
5752 */
5762 /* Get Collision result for query ::ER_COLL_QUERY_TYPE_DISTANCE
5763 */
5773 
5774 /* Get Collision result for query ::ER_COLL_QUERY_TYPE_TOLERANCE
5775 */
5785 
5786 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5787 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5788 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5789 // class ERK_CAPI_GEO
5790 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5791 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5792 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5793 
5794 /* erUpdateGeo
5795  Update all Models for each robot joint
5796 */
5805 DLLAPI long ER_STDCALL erUpdateGeo(ER_HND er_hnd);
5806 
5807 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5808 // class ERK_CAPI_GEO_MNGR
5809 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5810 //~~~~~~~~~~~~~~~~~~~~~
5811 // Administration
5812 //~~~~~~~~~~~~~~~~~~~~~
5817 
5824 
5832 
5833 //~~~~~~~~~~~~~~~~~~~~~
5834 // Access to geometries
5835 //~~~~~~~~~~~~~~~~~~~~~
5842 // fills structure pointed to by p_load_geometry_data with geometry loading data
5843 DLLAPI int ER_STDCALL erGeoMngr_GetGeometry(ER_HND er_hnd, int geometryIndex, LOAD_GEOMETRY_DATA *p_load_geometry_data, DFRAME* kinMat);
5844 // return number of geometries for axis of a specified device
5845 DLLAPI int ER_STDCALL erGeoMngr_GetNumAxisGeometries(ER_HND er_hnd, int axis_nr);
5846 // fills structure pointed to by p_load_geometry_data with geometry loading data
5847 DLLAPI int ER_STDCALL erGeoMngr_GetAxisGeometry(ER_HND er_hnd, int axis_nr, int geometryIndex, LOAD_GEOMETRY_DATA *p_load_geometry_data, DFRAME* kinMat);
5848 // BBox über die gesamte Geometrie (also über den gesamten Body)
5849 DLLAPI const double* ER_STDCALL erGeoMngr_GetGeometryBBox(TErGeoHandle geometryHandle);
5850 // Achsen-BBox über alle Geometry-BBoxes einer Achse
5851 DLLAPI const double* ER_STDCALL erGeoMngr_GetAxisBBox(ER_HND er_hnd, int axis_id);
5852 // Device-BBox
5853 DLLAPI const double* ER_STDCALL erGeoMngr_GetDeviceBBox(ER_HND er_hnd);
5854 
5856 
5857 DLLAPI int ER_STDCALL erGeoMngr_GetGeometryObjNumPoints(TErGeoHandle geometryHandle, int objidx);
5858 DLLAPI double* ER_STDCALL erGeoMngr_GetGeometryObjPoint(TErGeoHandle geometryHandle, int objidx, int index);
5860 DLLAPI double* ER_STDCALL erGeoMngr_GetGeometryObjPointNormal(TErGeoHandle geometryHandle, int objidx, int index);
5861 DLLAPI int ER_STDCALL erGeoMngr_GetGeometryObjNumLines(TErGeoHandle geometryHandle, int objidx);
5862 DLLAPI size_t* ER_STDCALL erGeoMngr_GetGeometryObjLine(TErGeoHandle geometryHandle, int objidx, int index);
5863 DLLAPI int ER_STDCALL erGeoMngr_GetGeometryObjNumPolygons(TErGeoHandle geometryHandle, int objidx);
5864 DLLAPI size_t* ER_STDCALL erGeoMngr_GetGeometryObjPolygon(TErGeoHandle geometryHandle, int objidx, int index);
5865 
5866 // ist die Obj-Color intern -2 (USER_COLOR) wird die user color (die Farbe, die in der LOAD_GEOMETRY_DATA-Struktur steht) zurückgegeben
5867 // sonst : konkrete Farbe
5868 DLLAPI double* ER_STDCALL erGeoMngr_GetGeometryObjColor(TErGeoHandle geometryHandle, int objidx);
5869 // der Farbcode (kann auch -2 (USER_COLOR) sein, damit die Host-Applikation eine eigene UserColor festlegen kann)
5870 DLLAPI long ER_STDCALL erGeoMngr_GetGeometryObjColorCode(TErGeoHandle geometryHandle, int objidx);
5871 
5872 DLLAPI int ER_STDCALL erGeoMngr_GetGeometryCloneCount(TErGeoHandle geometryHandle); // Get number of clones >=1
5874 
5875 //DLLAPI double* ER_STDCALL erGeoMngr_GetGeometryPolygoneNormal(TErGeoHandle geometryHandle, int index);
5876 //DLLAPI double* ER_STDCALL erGeoMngr_GetGeometryPolygoneCenter(TErGeoHandle geometryHandle, int index);
5877 
5880 DLLAPI int ER_STDCALL erGeoMngr_SetGeometryIsCollided(TErGeoHandle geometryHandle, int isCollided);
5882 
5883 DLLAPI int ER_STDCALL erGeoMngr_CheckBoundingBoxCollision(DFRAME* T1, const double* bbox1, DFRAME* T2, const double* bbox2, double tolerance);
5884 
5885 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5886 // class ERK_CAPI_SYS
5887 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5888 
5889 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5890 // class ERK_CAPI_SYS_UTILITIES
5891 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5892 
5893 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5894 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5895 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5896 // erMath_ - Functions
5897 // ERK_CAPI_SYS_MATHEMATICS
5898 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5899 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5900 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5915 DLLAPI long ER_STDCALL erMath_FrameToVecIdx(DFRAME *T, double *vec, long rotation_idx=ER_ROT_XYZ);
5916 
5931 DLLAPI long ER_STDCALL erMath_VecToFrameIdx(double *vec, DFRAME *T, long rotation_idx=ER_ROT_XYZ);
5932 
5947 DLLAPI long ER_STDCALL erMath_PxyzRxyzToFrame(double x,double y,double z,double Rx,double Ry,double Rz, DFRAME *T);
5948 
5956 DLLAPI long ER_STDCALL erMath_Frame_Ident(DFRAME *T); // T = Ident
5957 
5968 DLLAPI long ER_STDCALL erMath_Frame_Trans(DFRAME *T, double x, double y, double z); // set frame position T.p[] = [x,y,z]
5969 
5981 DLLAPI long ER_STDCALL erMath_Frame_Rot(DFRAME *T, double q, long rotation_idx=ER_ROT_IDENT); // rotation_idx = ER_ROT_IDENT, ER_ROT_X, ER_ROT_Y, ER_ROT_Z, T = f(q,rotation_idx)
5982 
5993 DLLAPI long ER_STDCALL erMath_AngleBetween(DFRAME *Ts, DFRAME *Te, double *angle, double *k=NULL);
5994 
6005 DLLAPI long ER_STDCALL erMath_DistBetween(DFRAME *Ts, DFRAME *Te, double *dist, double *dv=NULL);
6006 
6015 DLLAPI long ER_STDCALL erMath_invT(DFRAME *To,DFRAME *Ti); // To = inv(Ti)
6016 
6025 DLLAPI long ER_STDCALL erMath_invR(DFRAME *Ro,DFRAME *Ri); // Ro = inv(Ri) = transpose(Ri) = Ri'
6026 
6036 DLLAPI long ER_STDCALL erMath_mul_R_R(DFRAME *Ro,DFRAME *Ri1,DFRAME *Ri2); // Ro = Ri1 * Ri2
6037 
6047 DLLAPI long ER_STDCALL erMath_mul_T_T(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2); // To = Ti1 * Ti2
6048 
6060 DLLAPI long ER_STDCALL erMath_mul_T_invT (DFRAME *To, DFRAME *Ti1, DFRAME *Ti2); // To = Ti1 * inv(Ti2)
6061 
6073 DLLAPI long ER_STDCALL erMath_mul_invT_T (DFRAME *To, DFRAME *Ti1, DFRAME *Ti2); // To = inv(Ti1) * Ti2
6074 
6086 DLLAPI long ER_STDCALL erMath_mul_invT_invT (DFRAME *To, DFRAME *Ti1, DFRAME *Ti2); // To = inv(Ti1) * inv(Ti2)
6087 
6098 DLLAPI long ER_STDCALL erMath_mul_T_pos (double *po,DFRAME *T,double *pi); // po = T * pi
6099 
6111 DLLAPI long ER_STDCALL erMath_mul_invT_pos (double *po,DFRAME *T,double *pi); // po = inv(T) * pi
6112 
6122 DLLAPI long ER_STDCALL erMath_mul_R_pos (double *po,DFRAME *R,double *pi); // po = R * pi
6123 
6135 DLLAPI long ER_STDCALL erMath_mul_invR_pos (double *po,DFRAME *R,double *pi); // po = R' * pi
6136 
6147 DLLAPI long ER_STDCALL erMath_mul_T_T_T(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = Ti1 * Ti2 * Ti3
6148 
6161 DLLAPI long ER_STDCALL erMath_mul_T_T_invT(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = Ti1 * Ti2 * inv(Ti3)
6162 
6175 DLLAPI long ER_STDCALL erMath_mul_T_invT_T(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = Ti1 * inv(Ti2) * Ti3
6176 
6189 DLLAPI long ER_STDCALL erMath_mul_T_invT_invT(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = Ti1 * inv(Ti2) * inv(Ti3)
6190 
6203 DLLAPI long ER_STDCALL erMath_mul_invT_T_T(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = inv(Ti1) * Ti2 * Ti3
6204 
6217 DLLAPI long ER_STDCALL erMath_mul_invT_T_invT(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = inv(Ti1) * Ti2 * inv(Ti3)
6218 
6231 DLLAPI long ER_STDCALL erMath_mul_invT_invT_T(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = inv(Ti1) * inv(Ti2) * Ti3
6232 
6245 DLLAPI long ER_STDCALL erMath_mul_invT_invT_invT(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = To = inv(Ti1) * inv(Ti2) * inv(Ti3)
6246 
6257 DLLAPI double* ER_STDCALL erMath_SetVec6(double *vec, double q1,double q2,double q3,double q4,double q5,double q6); // cpy vector of size n
6270 DLLAPI double* ER_STDCALL erMath_SetVec6PosOri(double *vec, double x,double y,double z,double Rx,double Ry,double Rz); // cpy vector of size n, x,y,z in [mm], Rx,Ry,Rz in [deg]
6282 DLLAPI double* ER_STDCALL erMath_SetVec_n(double *vec, int n, double q1,double q2,double q3,double q4,double q5,double q6); // cpy vector of size n
6289 DLLAPI double* ER_STDCALL erMath_CpyVec(double *dst, double *src, int n); // cpy vector of size n
6295 DLLAPI double* ER_STDCALL erMath_ResetVec(double *dst, int n); // reset vector of size n
6296 
6297 //------------------------------------------------------------------------------------------
6298 //------------------------------------------------------------------------------------------
6299 
6300 #ifdef __cplusplus
6301 }
6302 #endif
6303 
6304 #endif // _er_kernel_main_h
DLLAPI long ER_STDCALL erColl_UnloadModel(ER_COLLISION_HND *er_coll_hnd)
Unload a Model. Free all allocated memory.
unsigned int * ER_HND
unique Kinematics handle, created with erInitKin()
Definition: erk_capi_types.h:187
DLLAPI long 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 f...
const long ER_COLL_QUERY_TYPE_COLLIDE
detects collision between two PQP_Models, erColl_ChkCollision()
Definition: erk_capi_types.h:716
DLLAPI long ER_STDCALL erFindConfig(ER_HND er_hnd, long *config)
Find current robot configuration Finds current robot configuration, depending on current robot joint ...
DLLAPI long ER_STDCALL erGetConfig(ER_HND er_hnd, long *config)
Get current robot configuration Gets current robot configuration. See also erSetConfig(). The config is valid for 1 to number of possible configurations, see erGetNumConfigs().
DLLAPI long ER_STDCALL erGetSweMin_passive(ER_HND er_hnd, double *swe_min_passive)
Get fix minimum travel ranges from passive joints. The kinematics travel ranges swe_min_passive are i...
DLLAPI long *ER_STDCALL erGetExtAxTrack_sync_type(ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND hnd)
Synchonization for Track/Slider For a Track/Slider motion, the synchonization should be always ER_SY...
DLLAPI long ER_STDCALL erGet_num_dofs_passive(ER_HND er_hnd)
Get number of passive robot joints.
DLLAPI ER_TARGET_EXTAX_DEVICE_POSITIONER_HND ER_STDCALL GetExtAxPositionerTemplate(ER_TOOLPATH_HND er_tpth_hnd)
Get external axis positioner template data from tool path. Get the external axis positioner template ...
DLLAPI long ER_STDCALL erKernelSetLicensePriority(int license_priority)
Set license priority. Call this function before initializing the Kernel erKernelInitialize() Paramete...
DLLAPI long ER_STDCALL erGetJoints_passive(ER_HND er_hnd, double *q_passive)
Get passive robot joint data. The kinematics passive joint data q_passive are in units [m] for prisma...
DLLAPI long ER_STDCALL erSetAxMax(ER_HND er_hnd, double ax_max)
Set maximum cartesian acceleration.
DLLAPI double *ER_STDCALL erMath_SetVec6PosOri(double *vec, double x, double y, double z, double Rx, double Ry, double Rz)
Cpy and convert a target location (position+orientation) to a vector position x,y,z in [mm] converted to [m] by ER_mm2m orientation Rx,Ry,Rz in [deg] converted to [rad] by ER_RAD .
DLLAPI long ER_STDCALL erToolPathEnable(ER_TOOLPATH_HND er_tpth_hnd, long enable)
Enable or disable tool path Parameter enable is one of ER_ONOFF_DISABLE, ER_ONOFF_ENABLE, ER_ONOFF_STATUS.
DLLAPI long ER_STDCALL erSetJointFrameActiveNext(ER_HND er_hnd, long active_jnt_no, DFRAME *T)
DLLAPI long ER_STDCALL erGetJointName_passive(ER_HND er_hnd, long passive_jnt_no, char *jnt_name_passive)
Get the name of passive robot joint.
Homogeneous 4x4 transformation matrix, a Frame with 3x3 orthogonal noa-matrix (n = o x a) and 3x1 pos...
Definition: erk_capi_types.h:81
DLLAPI double *ER_STDCALL erGetMotionAttributes_ramp(ER_TARGET_ATTRIBUTES_HND hnd)
Change of acceleration and deceleration as percentage value in the range from 20% to 100% of normal v...
DLLAPI ER_TOOLPATH_HND ER_STDCALL erGetTargetLocationToolPathHnd(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Tool path handle belonging to target location handle.
Contains target data for next move This structure contains all required data for the next target Usag...
DLLAPI long ER_STDCALL erGetInvKinID(ER_HND er_hnd, long *invkin_id)
Inverse kinematics ID for cRobot. .
DLLAPI long 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()
DLLAPI char *ER_STDCALL erGetTargetLocationName(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Name of target location.
DLLAPI long ER_STDCALL erInitToolPath(ER_HND er_hnd, ER_TOOLPATH_HND *er_tpth_hnd)
Create a unique tool path handle for a kinematics.
DLLAPI void **ER_STDCALL erGet_erk_kin_usr_ptr(ER_HND er_hnd)
DLLAPI long ER_STDCALL erMath_Frame_Trans(DFRAME *T, double x, double y, double z)
Set position of homogeneous 4x4 transformation matrix. T.p[] = [x,y,z] A frame DFRAME is a homogeneou...
unsigned int * ER_TARGET_MOVE_CP_HND
unique Target data for CP Move handle
Definition: erk_capi_types.h:201
DLLAPI long ER_STDCALL erGetExtTcpMode(ER_HND er_hnd, long *ext_tcp_mode)
Get external TCP mode. The external TCP can be IPO_MODE_BASE (tool guided) or IPO_MODE_TOOL (work obj...
DLLAPI double *ER_STDCALL erGetMoveJoint_JointPos(ER_TARGET_MOVE_JOINT_HND hnd)
Joint position for joint move for target location Remarks Use for.
DLLAPI double *ER_STDCALL erGetMoveCP_accel_cp(ER_TARGET_MOVE_CP_HND hnd)
Cartesian acceleration [m/s^2], for CP move for target location.
DLLAPI int ER_STDCALL erGeoMngr_GetGeometryNumObjs(TErGeoHandle geometryHandle)
DLLAPI long ER_STDCALL erSELECT_FLYBY_CRITERIA(ER_HND er_hnd, long param_number)
Selects a flyby criterion (parameter). Opcode 142, Chapter 3.4.6, Page 3-87 Function not supported ...
DLLAPI void ER_STDCALL erSetCallBack_LogProc(TerLogProc Handler)
Define Callback function for Log Messages.
DLLAPI long ER_STDCALL erGET_MESSAGE(ER_HND er_hnd, long message_number)
Gives information about controller messages that occurred. Opcode 154, Chapter 3.4.9, Page 3-104 Function not supported Use notify messages instead TErNotifyData.
DLLAPI long ER_STDCALL erColl_BeginModel(ER_COLLISION_HND *er_coll_hnd, long n_tris)
Creates a collision handle for one Model and preallocate memory for n_tris triangles.
DLLAPI long ER_STDCALL erSELECT_TRAJECTORY_MODE(ER_HND er_hnd, long trajectory_on)
Selects on or off for the trajectory mode. Opcode 122, Chapter 3.4.4, Page 3-62 The trajectory_on can...
DLLAPI long ER_STDCALL erSELECT_FLYBY_MODE(ER_HND er_hnd, long flyby_on)
Defines rounding / flyby condition. Opcode 140, Chapter 3.4.6, Page 3-85 Per default Flyby is disable...
DLLAPI long ER_STDCALL erGetJointSpeeds(ER_HND er_hnd, double *v_solut)
Get robot joint speeds. The kinematics joint speeds v_solut are in units [m/s] for prismatic joint ty...
DLLAPI long *ER_STDCALL erGetMotionAttributes_advance_motion(ER_TARGET_ATTRIBUTES_HND hnd)
Number of motions, the motion planner may run in advance of the interpolator (look_ahead) for a targe...
DLLAPI double *ER_STDCALL erGetMoveCP_CartPosVecVia(ER_TARGET_MOVE_CP_HND hnd)
Cartesian position at VIA location w.r.t. Base for CP move for target location Remarks Use for...
DLLAPI long ER_STDCALL erGetBaseRobotBase(ER_HND er_hnd, DFRAME *bTbase)
Get $BASE (wobj) w.r.t robot base. The $BASE frame has only effect when IPO_MODE_BASE is set in erSet...
DLLAPI long ER_STDCALL erTERMINATE(ER_HND *er_hnd)
Terminates an instance of a robot of the Kernel Opcode 103, Chapter 3.4.1, Page 3-30 See erUnloadKin(...
DLLAPI long ER_STDCALL erSetHomepos(ER_HND er_hnd, double *homepos)
Set robot joint homeposition. The kinematics joint homepos are in units [m] for prismatic joint type ...
long(ER_STDCALL * TerUpdateGeometryProc)(ER_HND ErHandle, TErGeoHandle GeoHandle, DFRAME *KinMat)
Callback function type definition to update a geometry, erSetCallBack_UpdateGeometryProc() ...
Definition: erk_capi_types.h:611
DLLAPI long ER_STDCALL erTargetLocationValid(ER_TARGET_LOCATION_HND er_tarloc_hnd, long valid)
Validity of a target location A target location is per default invalid when created e...
DLLAPI long ER_STDCALL erSET_NEXT_TARGET(ER_HND er_hnd, NEXT_TARGET_DATA *p_next_target_data)
Sends the next target position. This may include intermediate position, radius and angle for circular...
DLLAPI long ER_STDCALL erToolPathSetTrackMotionHandle(ER_TOOLPATH_HND er_tpth_hnd, ER_HND hnd_TrackMotion=NULL)
Set track motion handle belonging to tool path handle. The tool path handles the track motion device ...
DLLAPI ER_TARGET_MOVE_JOINT_HND ER_STDCALL erGetTargetLocationMoveJointHnd(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Handle for target move joint data Typical data belonging to a move joint target location are: target_...
DLLAPI long ER_STDCALL erToolPathGetTargetLocationNumber(ER_TOOLPATH_HND er_tpth_hnd)
Get the number of target locations in tool path.
DLLAPI char *ER_STDCALL erToolPathPrgFileName(ER_TOOLPATH_HND er_tpth_hnd)
Name program file.
#define ER_STDCALL
Definition: erk_capi_types.h:72
DLLAPI long ER_STDCALL erSetJoint(ER_HND er_hnd, double q_solut, long jnt_no)
Set a single robot joint data. The kinematics joint data q_solut are in units [m] for prismatic joint...
DLLAPI long ER_STDCALL erMath_mul_invT_invT_T(DFRAME *To, DFRAME *Ti1, DFRAME *Ti2, DFRAME *Ti3)
Tripple multiplication of homogeneous 4x4 transformation matrices. To = inv(Ti1) * inv(Ti2) * Ti3 Rem...
DLLAPI long *ER_STDCALL erGetMoveCP_target_type(ER_TARGET_MOVE_CP_HND hnd)
Target type for CP move for target location is always.
DLLAPI long *ER_STDCALL erGetExtAxPositioner_number_extax_used(ER_TARGET_EXTAX_DEVICE_POSITIONER_HND hnd)
Number of external axis used for Positioner/TurnTable see example GetExtAxPositionerHnd() ...
DLLAPI long ER_STDCALL erGetNumConfigs(ER_HND er_hnd, long *num_configs)
Get number of possible robot configurations.
DLLAPI long ER_STDCALL erGetJointName(ER_HND er_hnd, long active_jnt_no, char *jnt_name)
Get the name of active robot joint.
DLLAPI long ER_STDCALL erGetSweMaxCalc(ER_HND er_hnd, double *swe_max_calc)
Get calculated maximum travel ranges. The kinematics calculated travel ranges swe_max_calc are in uni...
void(ER_STDCALL * TerLogProc)(long LogType, char *LogMessage)
Callback function type definition for Log messages, erSetCallBack_LogProc()
Definition: erk_capi_types.h:595
DLLAPI long ER_STDCALL erSET_CARTESIAN_POSITION_ACCELERATION(ER_HND er_hnd, double accel_value, long accel_type)
Sets acceleration for cartesian motion [m/sec^2]. Opcode 137, Chapter 3.4.5, Page 3-78...
DLLAPI ER_TARGET_LOCATION_HND ER_STDCALL erGET_NEXT_TOOLPATH_STEP_cTargetLocation(ER_TOOLPATH_HND er_tpth_hnd)
Get the current &#39;target location handle&#39; while interpolation through a complete tool path...
DLLAPI long ER_STDCALL erGetJointTypes(ER_HND er_hnd, long *jnt_type_active)
Get active robot joint types. An active robot joint type can be rotational JNT_TYPE_ROT or prismatic ...
DLLAPI long ER_STDCALL erMath_mul_invT_T(DFRAME *To, DFRAME *Ti1, DFRAME *Ti2)
Multiplication of two homogeneous 4x4 transformation matrices. To = inv(Ti1) * Ti2 Remarks inv(T) is...
DLLAPI char *ER_STDCALL erToolPathLogFileName(ER_TOOLPATH_HND er_tpth_hnd)
Name log file.
DLLAPI long ER_STDCALL erSetTargetLocation_Move_SlewAbs(ER_TARGET_LOCATION_HND er_tarloc_hnd, double *JointPos, double speed_percent=0, double override_speed=0, double *Tool=0)
Move_SlewAbs, not synchronized PTP, motion definition for target location Remarks Use erAddTargetLoc...
DLLAPI long *ER_STDCALL erGetMoveCP_circ_orientation_interpolation_mode(ER_TARGET_MOVE_CP_HND hnd)
Circular orientation interpolation mode for CP move for target location The circular orientation inte...
DLLAPI ER_TARGET_MOVE_JOINT_HND ER_STDCALL GetMoveJointTemplate(ER_TOOLPATH_HND er_tpth_hnd)
Get move joint template data from tool path. Get the move joint template data belonging to the tool p...
DLLAPI int ER_STDCALL erGeoMngr_GetGeometryObjNumPointNormals(TErGeoHandle geometryHandle, int objidx)
DLLAPI long *ER_STDCALL erGetMotionAttributes_extTcpOffsetIdx(ER_TARGET_ATTRIBUTES_HND hnd)
Idx for external Tool/TCP offset data w.r.t. extTcpBase, extTcpWorld, for a target location see inq_e...
DLLAPI long ER_STDCALL erToolPathSetInitPos(ER_TOOLPATH_HND er_tpth_hnd, double InterpolationTime=0)
Initializes the Trajectory Planner based on current settings. Remarks This method must be called bef...
DLLAPI double *ER_STDCALL erMath_SetVec_n(double *vec, int n, double q1, double q2, double q3, double q4, double q5, double q6)
Cpy n values to a vector.
DLLAPI long ER_STDCALL erSetExtTcpMode(ER_HND er_hnd, long ext_tcp_mode)
Set external TCP mode. The external TCP can be IPO_MODE_BASE (tool guided) or IPO_MODE_TOOL (work obj...
DLLAPI long ER_STDCALL erKernelGetOptions(char *opt)
Supplies option string containing all enabled options.
DLLAPI ER_HND ER_STDCALL erToolPathGetPositionerHandle(ER_TOOLPATH_HND er_tpth_hnd)
Get device positioner handle belonging to tool path handle.
const long ER_ROT_IDENT
Rotation Index: Identity, erMath_Frame_Rot()
Definition: erk_capi_types.h:693
DLLAPI int *ER_STDCALL erGeoMngr_GetGeometryIsCollided(TErGeoHandle geometryHandle)
DLLAPI long ER_STDCALL erToolPathResetInitPositioner(ER_TOOLPATH_HND er_tpth_hnd, double *q_start=NULL)
Set initial joint start location for the Positioner. Remarks Read current joint data from loaded Pos...
long(ER_STDCALL * TerFreeGeometryProc)(ER_HND ErHandle, TErGeoHandle GeoHandle)
Callback function type definition to free or delete a geometry, erSetCallBack_FreeGeometryProc(). This callback function is used when unloading a kinemaitcs erUnloadKin() or a tool erUnloadTool()
Definition: erk_capi_types.h:620
DLLAPI long ER_STDCALL erToolPathSetPositionerHandle(ER_TOOLPATH_HND er_tpth_hnd, ER_HND hnd_Positioner=NULL)
Set positioner handle belonging to tool path handle. The tool path handles the positioner device as e...
Collision results for query ER_COLL_QUERY_TYPE_TOLERANCE, see erColl_GetResults_Tolerance() ...
Definition: erk_capi_types.h:773
DLLAPI long ER_STDCALL erSetBacklink(ER_HND er_hnd, long backlink)
Set robot back link status The back link status can be one of the following values. KIN_BACK_LINK_NO=0, KIN_BACK_LINK_YES =1 or KIN_BACK_LINK_UNKNOWN =2 see also erGetBacklink()
DLLAPI void ER_STDCALL erSetCallBack_UpdateGeometryProc(TerUpdateGeometryProc Handler)
Define Callback function to updat a geometries The Host application is prompted to update a geometry...
DLLAPI ER_TARGET_LOCATION_HND ER_STDCALL erGetTargetLocationLast(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Get last target location in a tool path.
DLLAPI long ER_STDCALL erGetBaseWorld(ER_HND er_hnd, DFRAME *iTbase)
Get $BASE (wobj) w.r.t inertia (world). The $BASE frame has only effect when IPO_MODE_BASE is set in ...
DLLAPI double *ER_STDCALL erGetMotionAttributes_flyby_dist(ER_TARGET_ATTRIBUTES_HND hnd)
flyby by distance [m] for a target location In case of flyby by distance, the robot starts moving int...
DLLAPI long ER_STDCALL erMath_mul_invT_invT_invT(DFRAME *To, DFRAME *Ti1, DFRAME *Ti2, DFRAME *Ti3)
Tripple multiplication of homogeneous 4x4 transformation matrices. To = inv(Ti1) * inv(Ti2) * inv(Ti3...
DLLAPI long ER_STDCALL erGetSweMinMaxCalc(ER_HND er_hnd, double *swe_min_calc, double *swe_max_calc)
Get calculated minimum and maximum travel ranges. The kinematics calculated travel ranges swe_min_cal...
DLLAPI double *ER_STDCALL erGetMoveJoint_speed_percent(ER_TARGET_MOVE_JOINT_HND hnd)
Speed_percent percentage speed definition [&gt;0-1000%] for joint move for target location.
unsigned int * ER_TARGET_EXTAX_DEVICE_POSITIONER_HND
unique External axis data definition for Positioner/TurnTable handle
Definition: erk_capi_types.h:204
DLLAPI double *ER_STDCALL erGetMoveCP_speed_ori(ER_TARGET_MOVE_CP_HND hnd)
Cartesian orientation speed [rad/s], for CP move for target location.
DLLAPI long *ER_STDCALL erGetMoveJoint_target_type(ER_TARGET_MOVE_JOINT_HND hnd)
Target type for joint move for target location is one of.
DLLAPI char *ER_STDCALL erGetMotionAttributes_extTcpBaseName(ER_TARGET_ATTRIBUTES_HND hnd)
Name for external Tool (TCP) w.r.t. Robot Base or flange of positioner, for a target location see inq...
DLLAPI long ER_STDCALL erKernelSetLicenseFile(char *license_file)
Set location and name of license file. Call this function before initializing the Kernel erKernelInit...
DLLAPI const double *ER_STDCALL erGeoMngr_GetDeviceBBox(ER_HND er_hnd)
DLLAPI long ER_STDCALL CpyMoveCPTemplate(ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_MOVE_CP_HND hnd)
Copy move cp data to template data. The move cp data defined with move cp handle hnd are copied to th...
DLLAPI void ER_STDCALL erSetCallBack_GrpSyncProc(TerGrpSyncProc Handler)
Define Callback function for group synchonization.
DLLAPI long ER_STDCALL erTPth_Fct(ER_TOOLPATH_HND er_tpth_hnd)
Do Fct. ... tbd.
DLLAPI ER_EXTAX_KIN_DATA *ER_STDCALL erGetExtAxConveyor_extax_data(ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND hnd, long extax_idx)
External axis values for Conveyor Values ER_EXTAX_KIN_DATA are: .
DLLAPI long ER_STDCALL erKernelGetOptionsDisabled(char *nopt)
Supplies option string containing all disabled options.
DLLAPI int ER_STDCALL erGeoMngr_GetAxisGeometry(ER_HND er_hnd, int axis_nr, int geometryIndex, LOAD_GEOMETRY_DATA *p_load_geometry_data, DFRAME *kinMat)
DLLAPI long ER_STDCALL erSetTargetLocation_Move_JointAbs(ER_TARGET_LOCATION_HND er_tarloc_hnd, double *JointPos, double speed_percent=0, double override_speed=0, double *Tool=0)
Move_JointAbs, full synchronized PTP, motion definition for target location Remarks Use erAddTargetL...
DLLAPI int ER_STDCALL erGeoMngr_GetNumAxisGeometries(ER_HND er_hnd, int axis_nr)
DLLAPI long ER_STDCALL erSELECT_CIRCULAR_ORIENTATION_INTERPOLATION_MODE(ER_HND er_hnd, long circ_orientation_interpolation_mode)
Selects the circular orientation interpolation mode. The parameter circ_orientation_interpolation_mod...
DLLAPI long ER_STDCALL erSetTrackingWindow(ER_HND er_hnd, long active, double up, double down, TErTrackingWindowID id_tw, char *name=NULL)
Activates and deactivates the boundaries for a Tracking Window. This function enables a tracking wind...
DLLAPI long ER_STDCALL erGetMotionExec_configuration(ER_TARGET_MOTION_EXEC_HND hnd)
Robot configuration, when reaching the target, while interpolation trough the complete tool path Rema...
DLLAPI long ER_STDCALL erGetBackLink(ER_HND er_hnd, long *backlink)
Get robot back link status, obsolete function, use erGetBacklink()
DLLAPI char *ER_STDCALL erGetInstructions_information(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Get information target instruction data for target location. For further explanations see GetInstruct...
DLLAPI ER_HND ER_STDCALL erConnectTrackMotionGetHND(ER_HND er_hnd)
Get robots connection handle between robot and track motion. See also erConnectTrackMotion() ...
DLLAPI long ER_STDCALL erGET_EVENT(ER_HND er_hnd, long event_nr)
This function gets information about an internal asynchronous event that occurred in the Kernel...
DLLAPI long ER_STDCALL erSetJointFramePassiveLast(ER_HND er_hnd, long passive_jnt_no, DFRAME *T)
DLLAPI long ER_STDCALL erGetSweCalcMode(ER_HND er_hnd, long *swe_calc_mode)
Get calculation mode for travel ranges Travel ranges can be fixed or depending on joints by a formula...
DLLAPI long ER_STDCALL erColl_GetResults_Collide(ER_CollideResult *er_cres)
Get Collision result for query ER_COLL_QUERY_TYPE_COLLIDE. Remarks Call erColl_ChkCollision() first...
DLLAPI long ER_STDCALL erGetVxOriMax(ER_HND er_hnd, double *vx_ori_max)
Get maximum cartesian orientation speed.
DLLAPI long ER_STDCALL erConnectConveyorGetSync(ER_HND er_hnd)
Get robots synchronization flag for synchronization between robot and conveyor. See also erConnectCon...
unsigned int * ER_TARGET_LOCATION_HND
unique Target location handle, created with erAddTargetLocation()
Definition: erk_capi_types.h:195
DLLAPI ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND ER_STDCALL GetExtAxTrackMotionTemplate(ER_TOOLPATH_HND er_tpth_hnd)
Get external axis track motion template data from tool path. Get the external axis track motion templ...
DLLAPI long ER_STDCALL erMath_mul_invR_pos(double *po, DFRAME *R, double *pi)
Multiplication of a 3x1 position with the transpose of a 3x3 orientation of a homogeneous 4x4 transfo...
DLLAPI long ER_STDCALL erSELECT_TRACKING(ER_HND er_hnd, long conveyor_flags)
Selects the Tracking On or Off in the Kernel. Opcode 146, Chapter 3.4.7, Page 3-93 Function not suppo...
DLLAPI long ER_STDCALL erInvKinWorldTip(ER_HND er_hnd, DFRAME *iTt)
Calculating the inverse kinematics transformation. The iTt is the location of the flange w...
DLLAPI long *ER_STDCALL erGetMoveJoint_ptp_target_calculation_mode(ER_TARGET_MOVE_JOINT_HND hnd)
Ptp_target_calculation_mode for target location is one of ER_PTP_TARGET_CALC_MODE_SHORTEST_ANGLE, ER_PTP_TARGET_CALC_MODE_TURNS, ER_PTP_TARGET_CALC_MODE_MATH, ER_PTP_TARGET_CALC_MODE_IN_TRAVEL_RANGE, ER_PTP_TARGET_CALC_MODE_VAR_CONFIG.
DLLAPI int ER_STDCALL erGeoMngr_GetGeometryObjNumPolygons(TErGeoHandle geometryHandle, int objidx)
DLLAPI long ER_STDCALL erColl_ChkCollision(ER_COLLISION_HND er_coll_hnd_1, DFRAME *iT_1, ER_COLLISION_HND er_coll_hnd_2, DFRAME *iT_2, long query_type=ER_COLL_QUERY_TYPE_COLLIDE, long contact_type=ER_COLL_FIRST_CONTACT, double rel_err=0, double abs_err=0, double tolerance=0)
Perform the collision check of two Models. See also erColl_ChkCollision_res() to get the collision re...
DLLAPI long ER_STDCALL erMath_mul_R_R(DFRAME *Ro, DFRAME *Ri1, DFRAME *Ri2)
Orientation multiplication of two homogeneous 4x4 transformation matrices. Ro = Ri1 * Ri2 A frame DFR...
DLLAPI long ER_STDCALL erGetJointTypes_passive(ER_HND er_hnd, long *jnt_type_passive)
Get passive robot joint types. A passive robot joint type can be rotational JNT_TYPE_ROT or prismatic...
DLLAPI long ER_STDCALL erGetBacklink(ER_HND er_hnd, long *backlink)
Get robot back link status The back link status can be one of the following values. KIN_BACK_LINK_NO=0, KIN_BACK_LINK_YES =1 or KIN_BACK_LINK_UNKNOWN =2 see also erSetBacklink()
DLLAPI long ER_STDCALL erSET_PAYLOAD_PARAMETER(ER_HND er_hnd, long storage, char *frame_id, long param_number, double param_value)
Allows specifying payloads at different locations on the robot. It has to be supported when the paylo...
DLLAPI long ER_STDCALL erUnloadKin(ER_HND *er_hnd)
Unload an instance of kinematics of the Kernel. Unloads an instance of kinematics givin by the unique...
DLLAPI long ER_STDCALL erMath_mul_T_invT_T(DFRAME *To, DFRAME *Ti1, DFRAME *Ti2, DFRAME *Ti3)
Tripple multiplication of homogeneous 4x4 transformation matrices. To = Ti1 * inv(Ti2) * Ti3 Remarks ...
DLLAPI long ER_STDCALL erGetAxMax(ER_HND er_hnd, double *ax_max)
Get maximum cartesian acceleration.
DLLAPI void ER_STDCALL erEnableCallBack_LogProc(long onoff)
Enable/Disable Log messages. This function enables or disables Log Messages used with callback functi...
DLLAPI long ER_STDCALL erMath_mul_T_invT(DFRAME *To, DFRAME *Ti1, DFRAME *Ti2)
Multiplication of two homogeneous 4x4 transformation matrices. To = Ti1 * inv(Ti2) Remarks inv(T) is...
DLLAPI double *ER_STDCALL erMath_ResetVec(double *dst, int n)
Reset vector dst = 0.
DLLAPI long ER_STDCALL erSELECT_ORIENTATION_INTERPOLATION_MODE(ER_HND er_hnd, long interpolation_mode, long ori_const)
Set orientation interpolation mode. Opcode 123, Chapter 3.4.4, Page 3-63 The interpolation_mode is pe...
DLLAPI long 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_h...
DLLAPI long ER_STDCALL erMath_invR(DFRAME *Ro, DFRAME *Ri)
Builds the inverse of the 3x3 orientation matrix from a homogeneous 4x4 transformation matrix T...
DLLAPI long ER_STDCALL erSET_POINT_ACCURACY_PARAMETER(ER_HND er_hnd, long accuracy_type, double accuracy_value)
Sets the value of a parameter determining point accuracy. Opcode 145, Chapter 3.4.6, Page 3-90 Function not supported
DLLAPI long ER_STDCALL erRESET(ER_HND er_hnd)
Resets an instance of a robot to an initial state. Opcode 102, Chapter 3.4.1, Page 3-29 Settings are...
DLLAPI long ER_STDCALL erMath_Frame_Rot(DFRAME *T, double q, long rotation_idx=ER_ROT_IDENT)
Set orientation of homogeneous 4x4 transformation matrix. T = f(q,rotation_idx) The rotation index ro...
DLLAPI long *ER_STDCALL erGetExtAxPositioner_sync_type(ER_TARGET_EXTAX_DEVICE_POSITIONER_HND hnd)
Synchonization for Positioner/TurnTable For a Positioner/TurnTable motion, the synchonization can be...
DLLAPI int ER_STDCALL erGeoMngr_SetGeometryCollisionHandle(TErGeoHandle geometryHandle, ER_COLLISION_HND collisionHandle)
const int ER_MOP_GNTPS_CNTRL_INIT
Get Next Tool Path Step, Initialize ToolPath interpolation.
Definition: erk_capi_types.h:555
DLLAPI long ER_STDCALL erSetJoints(ER_HND er_hnd, double *q_solut)
Set robot joint data. The kinematics joint data q_solut are in units [m] for prismatic joint type an...
DLLAPI long ER_STDCALL erSET_NEXT_TARGET_ADVANCE(ER_HND er_hnd, NEXT_TARGET_DATA_ADVANCE *p_next_target_data_advance)
Sends about next target data The function gives information about the next target, stored in NEXT_TARGET_DATA_ADVANCE Remarks This function should be called once, just before calling erSET_NEXT_TARGET() Parameter AdvanceParam=2 sets all data in NEXT_TARGET_DATA_ADVANCE to default values.
DLLAPI ER_HND ER_STDCALL erConnectPositionerGetHND(ER_HND er_hnd)
Get robots connection handle between robot and positioner. See also erConnectPositioner() ...
DLLAPI char *ER_STDCALL erGetMotionAttributes_extTcpWorldName(ER_TARGET_ATTRIBUTES_HND hnd)
Name for external Tool (TCP) w.r.t. Robot World or flange of positioner, for a target location see in...
DLLAPI long ER_STDCALL erMath_mul_T_invT_invT(DFRAME *To, DFRAME *Ti1, DFRAME *Ti2, DFRAME *Ti3)
Tripple multiplication of homogeneous 4x4 transformation matrices. To = Ti1 * inv(Ti2) * inv(Ti3) Rem...
DLLAPI ER_HND ER_STDCALL erToolPathGetRobotHandle(ER_TOOLPATH_HND er_tpth_hnd)
Get device robot handle belonging to tool path handle.
DLLAPI long ER_STDCALL erSET_INITIAL_POSITION(ER_HND er_hnd, INITIAL_POSITION_DATA *p_initial_position_data)
Sets the robot model to a position according to the input data Opcode 116, Chapter 3...
Collision results for query ER_COLL_QUERY_TYPE_COLLIDE, see erColl_GetResults_Collide() ...
Definition: erk_capi_types.h:744
DLLAPI long ER_STDCALL erUnloadToolPath(ER_TOOLPATH_HND *er_tpth_hnd)
Unload an instance of a kinematics tool path.
DLLAPI long ER_STDCALL erToolPathResetInitRobot(ER_TOOLPATH_HND er_tpth_hnd, double *q_start=NULL)
Set initial joint start location for the robot. Remarks Read current joint data from loaded robot...
DLLAPI long ER_STDCALL erGetJointSolutions(ER_HND er_hnd, double *q_solutions, long *q_warnings)
Get all robot joint solutions. The kinematics joint data q_solutions are in units [m] for prismatic j...
DLLAPI double *ER_STDCALL erGetMotionAttributes_extTcpWorldVec(ER_TARGET_ATTRIBUTES_HND hnd)
external Tool (TCP) w.r.t. Robot World or flange of positioner, for a target location Transformation ...
DLLAPI long ER_STDCALL erGetJointAccels(ER_HND er_hnd, double *a_solut)
Get robot joint accelerations. The kinematics joint accelerations a_solut are in units [m/s^2] for pr...
unsigned int * ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND
unique External axis data definition for Track/Slider handle
Definition: erk_capi_types.h:203
DLLAPI long ER_STDCALL erSetBaseRobotBase(ER_HND er_hnd, DFRAME *bTbase)
Set $BASE (wobj) w.r.t robot base. The $BASE frame has only effect when IPO_MODE_BASE is set in erSet...
DLLAPI long ER_STDCALL erKernelGetLicenseFile(char *license_file)
Get location and name of license file. If license_file is not set the string is empty, see erKernelSetLicenseFile()
DLLAPI long ER_STDCALL erGetTurn_offset(ER_HND er_hnd, double *turn_offset)
Get the turn offset for each robot joints The kinematics turn offset turn_offset are in units [m] for...
DLLAPI double *ER_STDCALL erGetMotionAttributes_acc(ER_TARGET_ATTRIBUTES_HND hnd)
Acceleration and deceleration as percentage value in the range from 20% to 100% of normal values for ...
DLLAPI long ER_STDCALL erSetJointSign(ER_HND er_hnd, double *joint_sign)
Set sign of robot joints. A robot joint sign can be positive +1 or negative -1.
DLLAPI double *ER_STDCALL erGetMotionAttributes_BaseVec(ER_TARGET_ATTRIBUTES_HND hnd)
Program shift Base for a target location Base &#39;$BASE, $UFrame&#39; has only if IPO_MODE_BASE is set and e...
DLLAPI long ER_STDCALL erSetconveyorStartCondition(ER_HND er_hnd, double tx0)
Sets the conveyor start condition. This function set the conveyor start condition for the Tracking Wi...
DLLAPI long *ER_STDCALL erGetMotionAttributes_ext_tcp_mode(ER_TARGET_ATTRIBUTES_HND hnd)
Enables/disables external TCP for a target location IPO_MODE_BASE (tool guided) or IPO_MODE_TOOL (wor...
DLLAPI long ER_STDCALL erSET_CARTESIAN_ORIENTATION_SPEED(ER_HND er_hnd, long rotation_no, double speed_ori_value)
Sets the speed for the orientation during Cartesian motion. Opcode 134, Chapter 3.4.5, Page 3-76. The rotation_no should be 1.
DLLAPI double *ER_STDCALL erGetMotionAttributes_WobjCartPosVec(ER_TARGET_ATTRIBUTES_HND hnd)
WorkObject valid for all cartesian target locations such as CartPosVec, CartPosVecVia Using this tran...
DLLAPI double *ER_STDCALL erMath_CpyVec(double *dst, double *src, int n)
Cpy vector dst = src.
DLLAPI long ER_STDCALL erGetTurn_interval(ER_HND er_hnd, double *turn_interval)
Get the turn interval for each robot joints The kinematics turn interval turn_interval are in units [...
DLLAPI long ER_STDCALL erSET_JOINT_JERKS(ER_HND er_hnd, long all_joint_flags, long joint_flags, double jerk_percent, long jerk_type)
Sets the joint jerk expressed as a percentage of the maximal joint jerk for each specified joint...
DLLAPI long ER_STDCALL erGet_n_Kin_IR(ER_HND er_hnd)
Get the number of loaded kinematics with more than 3 joints and inverse kinematics.
DLLAPI long ER_STDCALL erColl_ChkCollision_res_free(long query_type, void *pres)
Frees allocated memory for Collision results for parameter pres The query type query_type can be one...
DLLAPI ER_HND ER_STDCALL erhGetTargetLocationER_HND(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Device handle belonging to target location.
DLLAPI long *ER_STDCALL erGetMoveJoint_configuration(ER_TARGET_MOVE_JOINT_HND hnd)
configuration Robot configuration [1-ER_KIN_CONFIGS] for target location
DLLAPI long ER_STDCALL erInsertToolPath(ER_HND er_hnd, ER_TOOLPATH_HND *er_tpth_hnd, ER_TOOLPATH_HND er_tpth_hnd_ref)
Create and insert a unique tool path handle. The created tool path handle er_tpth_hnd is inserted bef...
DLLAPI long ER_STDCALL erMath_FrameToVecIdx(DFRAME *T, double *vec, long rotation_idx=ER_ROT_XYZ)
Converts a frame into an euler vector or quaternion. Frame T is converted into a vector vec A frame ...
DLLAPI int ER_STDCALL erGeoMngr_GetGeometryObjNumPoints(TErGeoHandle geometryHandle, int objidx)
DLLAPI double ER_STDCALL erGetMotionExec_time_stamp(ER_TARGET_MOTION_EXEC_HND hnd)
Time stamp - total execution time [s] at the target location, while interpolation trough the complete...
DLLAPI long *ER_STDCALL erGetMotionAttributes_dom_type(ER_TARGET_ATTRIBUTES_HND hnd)
Dominant interpolation type for a target location The dominant interpolation type can be one of the f...
DLLAPI long ER_STDCALL erMath_VecToFrameIdx(double *vec, DFRAME *T, long rotation_idx=ER_ROT_XYZ)
Converts an euler vector or quaternion into a frame. Vector vec is converted into a frame T A frame ...
DLLAPI TErGeoHandle ER_STDCALL erGeoMngr_LoadGeometry(ER_HND er_hnd, LOAD_GEOMETRY_DATA *p_load_geometry_data)
Load a geometry.
DLLAPI double *ER_STDCALL erGetMotionAttributes_LagWaitTime(ER_TARGET_ATTRIBUTES_HND hnd)
Lagging time [s] after robot reaches its target location Remarks Default value: 0 Has only an effect...
DLLAPI ER_TARGET_MOVE_CP_HND ER_STDCALL GetMoveCPTemplate(ER_TOOLPATH_HND er_tpth_hnd)
Get move cp template data from tool path. Get the move cp template data belonging to the tool path er...
DLLAPI long ER_STDCALL erSetExtTcpWorld(ER_HND er_hnd, DFRAME *iText)
Set location of external TCP w.r.t inertia (world).
DLLAPI long ER_STDCALL erSET_OVERRIDE_ACCELERATION(ER_HND er_hnd, double correction_value, long accel_type, long correction_type)
Sets correction values for scaling the robot acceleration. Opcode 155, Chapter 3.4.5, Page 3-83. The accel_type specifies the type of acceleration and can be one of the following values. 1: Acceleration, 2: Deceleration, 3: Acceleration and deceleration. The parameter correction_type specifies when the correction is effective and can be one of the following values. 0: It becomes effective at the next call to erGET_NEXT_STEP() 1: It becomes effective for the next target supplied by erSET_NEXT_TARGET() See also erSET_OVERRIDE_ACCELERATION_EX()
DLLAPI long ER_STDCALL erSetConveyorStartOffsetCondition(ER_TARGET_LOCATION_HND er_tarloc_hnd, double tx0)
Sets the conveyor start offset condition. This function set the conveyor start condition for the Trac...
DLLAPI long ER_STDCALL erSetJointOffset(ER_HND er_hnd, double *joint_offset)
Set offset of robot joints. Robot joint offsets joint_offset are in units [m] for prismatic joint typ...
DLLAPI long ER_STDCALL erSetSweMin_passive(ER_HND er_hnd, double *swe_min_passive)
Set fix minimum travel ranges for passive joints. The kinematics travel ranges swe_min_passive are in...
DLLAPI long ER_STDCALL erGetJointFrameActiveLast(ER_HND er_hnd, long active_jnt_no, DFRAME *T)
DLLAPI long ER_STDCALL erSTOP_MOTION(ER_HND er_hnd)
Stops the on-going motion toward the target. Opcode 151, Chapter 3.4.8, Page 3-101 See also erCONTINU...
DLLAPI long ER_STDCALL erGetJointAttachDof_passive(ER_HND er_hnd, long *jnt_attach_dof_passive)
Get Attach-Dof of passive robot joints. A passive joint is attached to an active joint. A valid Attach-Dof number number is [0..num_dof], whereby num_dof represents the number of active joints A negative Attach-Dof represents an error.
DLLAPI long ER_STDCALL erGetJointDirections_passive(ER_HND er_hnd, long *jnt_direction_passive)
Get direction of passive robot joints. A robot joint direction can be JNT_DIRECTION_X, JNT_DIRECTION_Y or JNT_DIRECTION_Z See also erGetJointTypes_passive()
DLLAPI ER_TARGET_LOCATION_HND ER_STDCALL erGetTargetLocationPrev(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Get previous target location in a tool path.
DLLAPI long ER_STDCALL erSetSweMax_passive(ER_HND er_hnd, double *swe_max_passive)
Set fix maximum travel ranges for passive joints. The kinematics travel ranges swe_max_passive are in...
unsigned int * ER_TARGET_ATTRIBUTES_HND
unique Motion attributes handle
Definition: erk_capi_types.h:199
DLLAPI long ER_STDCALL erCANCEL_FLYBY_CRITERIA(ER_HND er_hnd, long param_number)
Cancels (unselects) a fly-by criterion. Opcode 143, Chapter 3.4.6, Page 3-88 Function not supported ...
DLLAPI long ER_STDCALL erCANCEL_EVENT(ER_HND er_hnd, long event_id)
This function makes it possible to cancel an event previously defined in the Kernel by the erDEFINE_E...
DLLAPI long ER_STDCALL erSET_OVERRIDE_POSITION(ER_HND er_hnd, DFRAME *PosOffset)
Sets a correction offset which will be added to the path during program execution. Opcode 129, Chapter 3.4.4, Page 3-69 This function can be used for sensor-compensated motion. It is effective at each time step. The passed value is valid until the function is called again.
const long ER_PTP_TARGET_CALC_MODE_UNDEF
default ER_PTP_TARGET_CALC_MODE_SHORTEST_ANGLE, NEXT_TARGET_DATA
Definition: erk_capi_types.h:387
#define DLLAPI
Definition: erk_capi_types.h:71
DLLAPI long ER_STDCALL erSetAccSet(ER_HND er_hnd, double acc, double ramp)
Set lagging of accelerations. Using AccSet is a proper way to come close to real cycle times when the...
DLLAPI long 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()
DLLAPI long ER_STDCALL erConnectConveyorSetSync(ER_HND er_hnd, long connect_sync)
Set robots synchronization flag for synchronization between robot and conveyor. The synchronization f...
DLLAPI double *ER_STDCALL erGetMotionAttributes_override_speed(ER_TARGET_ATTRIBUTES_HND hnd)
Correction values as percentage value for scaling the programmed speed for a target location Remarks ...
DLLAPI long ER_STDCALL erGetJointFrameRobotBase_passive(ER_HND er_hnd, long passive_jnt_no, DFRAME *bTax)
Get location of passive joint coorsys w.r.t robot base. Get the number of passive joints with erGet_n...
DLLAPI long ER_STDCALL erGetConfigName(ER_HND er_hnd, long config_idx, char *config_name)
Get the name of robot configuration. Get the number of configurations with erGetNumConfigs() ...
DLLAPI double *ER_STDCALL erGetMotionAttributes_LeadWaitTime(ER_TARGET_ATTRIBUTES_HND hnd)
Leading time [s] before robot will start moving to target location Remarks Default value: 0 Has only...
DLLAPI long ER_STDCALL CpyExtAxPositionerTemplate(ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_EXTAX_DEVICE_POSITIONER_HND hnd)
Copy external axis positioner data to template data. The external axis positioner data defined with e...
Contains desired data for next interpolation step Usage with erGET_NEXT_STEP()
DLLAPI ER_TARGET_MOTION_EXEC_HND ER_STDCALL erGetTargetLocationMotionExecHnd(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Handle for target execution data Target execution data are calculated while interpolation trough the ...
DLLAPI long *ER_STDCALL erGetMotionAttributes_extTcpBaseIdx(ER_TARGET_ATTRIBUTES_HND hnd)
Idx for external Tool (TCP) w.r.t. Robot Base or flange of positioner, for a target location see inq_...
DLLAPI char *ER_STDCALL erGetMotionAttributes_BaseName(ER_TARGET_ATTRIBUTES_HND hnd)
Name for program shift Base for a target location see inq_BaseVec(), inq_BaseIdx() This BaseName coul...
DLLAPI long ER_STDCALL erSetVxMax(ER_HND er_hnd, double vx_max)
Set maximum cartesian speed.
DLLAPI long ER_STDCALL CpyExtAxConveyorTemplate(ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND hnd)
Copy external axis conveyor data to template data. The external axis conveyor data defined with exter...
DLLAPI long ER_STDCALL erSetTurn_interval(ER_HND er_hnd, double *turn_interval)
Set the turn interval for each robot joints The kinematics turn interval turn_interval are in units [...
DLLAPI int ER_STDCALL erSetInstructions(ER_TARGET_LOCATION_HND er_tarloc_hnd, char *InfoTxt=NULL, char *LeadInst=NULL, char *LagInst=NULL)
Set target instruction data for information, leading- and lagging instruction. For further explanatio...
DLLAPI char *ER_STDCALL erGetInstructions_LagInstructions(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Get LagInstructions target instruction data for target location. For further explanations see GetInst...
DLLAPI long ER_STDCALL erMath_mul_invT_pos(double *po, DFRAME *T, double *pi)
Multiplication of a 3x1 position with the inverse of a homogeneous 4x4 transformation matrices...
DLLAPI long ER_STDCALL erSET_CARTESIAN_ORIENTATION_ACCELERATION(ER_HND er_hnd, long rotation_no, double accel_ori_value, long accel_type)
Sets acceleration for the orientation during cartesian motion [m/sec^2]. Opcode 138, Chapter 3.4.5, Page 3-79. The rotation_no should be 1. The accel_type specifies the type of acceleration and can be one of the following values. 1: Acceleration, 2: Deceleration, 3: Acceleration and deceleration.
DLLAPI long ER_STDCALL erGetTurn_value(ER_HND er_hnd, long *turn_value)
Get the turn value for each robot joints The turn value turn_value determine the desired Turn in the ...
DLLAPI double *ER_STDCALL erGetMotionExec_JointPos(ER_TARGET_MOTION_EXEC_HND hnd)
Joint position at target location, while interpolation trough the complete tool path.
External axis target data for connected devices belongs to structure NEXT_TARGET_DATA.
DLLAPI long ER_STDCALL erGetAutoAccel(ER_HND er_hnd, long *autoaccel)
Get status for automatic calculation of acceleration depending on programmed speed. Using AutoAccel is a proper way to come close to real cycle times. The parameter autoaccel specifies the effect when planning a new motion and can be one of the following values. 0: ER_AUTOACCEL_MODE_OFF disables auto accel calculation for all motions 1: ER_AUTOACCEL_MODE_POS calculation for CP motions for position 2: ER_AUTOACCEL_MODE_ORI calculation for CP motions 4: ER_AUTOACCEL_MODE_AX Calculation for PTP motions 3: ER_AUTOACCEL_MODE_DEF calculation for CP motions for position and for orientation 7: ER_AUTOACCEL_MODE_ON enables calculation for all motions Remarks If auto accel is enabled, other acceleration functions such as erSET_JOINT_ACCELERATIONS(), erSET_CARTESIAN_POSITION_ACCELERATION() and erSET_CARTESIAN_ORIENTATION_ACCELERATION() will have no effect.
DLLAPI long ER_STDCALL erGetSweMax(ER_HND er_hnd, double *swe_max)
Get fix maximum travel ranges. The kinematics travel ranges swe_max are in units [m] for prismatic jo...
DLLAPI long *ER_STDCALL erGetMotionAttributes_filter_factor(ER_TARGET_ATTRIBUTES_HND hnd)
Filter factor for smoothing velocity profiles of motions The filter_factor is one of ER_MOTION_FILTER...
DLLAPI long ER_STDCALL erUpdateGeo(ER_HND er_hnd)
Updates all geometry location for each robot joint. This function causes the call of callback functio...
DLLAPI long ER_STDCALL erMath_mul_invT_T_invT(DFRAME *To, DFRAME *Ti1, DFRAME *Ti2, DFRAME *Ti3)
Tripple multiplication of homogeneous 4x4 transformation matrices. To = inv(Ti1) * Ti2 * inv(Ti3) Rem...
DLLAPI long ER_STDCALL erSetAqMax(ER_HND er_hnd, double *aq_max)
Set maximum of robot joint accelerations. Robot joint accelerations aq_max are in units [m/s^2] for p...
DLLAPI double *ER_STDCALL erGetMoveJoint_accel_percent(ER_TARGET_MOVE_JOINT_HND hnd)
Accel_percent percentage acceleration definition [&gt;0-1000%] for joint move for target location...
DLLAPI long ER_STDCALL erUpdateKin(ER_HND er_hnd)
Updates the complete kinematics. This function calculates the location of all axis coorsys...
DLLAPI long ER_STDCALL erGetMoveBaseMode(ER_HND er_hnd, long *move_base_mode)
Gets moveable base mode. A kinematics base can be fixed or moveable. 0: Robot base is fix (default) 1...
DLLAPI long ER_STDCALL erGetWorldTcp(ER_HND er_hnd, DFRAME *iTw)
Get robot tcp location w.r.t. inertia (world) coorsys.
unsigned int TErGeoHandle
unique Geometry handle used for callback functions TerLoadGeometryProc()
Definition: erk_capi_types.h:189
DLLAPI long ER_STDCALL erSET_INTERPOLATION_TIME(ER_HND er_hnd, double InterpolationTime)
Sets the interpolation time. Opcode 119, Chapter 3.4.3, Page 3-56 Set the interpolation time step...
DLLAPI long ER_STDCALL erKernelGetVersion(void)
Returns the Kernels Version.
DLLAPI long *ER_STDCALL erGetMotionAttributes_motype(ER_TARGET_ATTRIBUTES_HND hnd)
Motion Type for a target location The motion type can be one of the following values ER_JOINT = ER_PT...
DLLAPI long ER_STDCALL erToolPathResetInitConveyor(ER_TOOLPATH_HND er_tpth_hnd, double *q_start=NULL)
Set initial joint start location for the Conveyor. Remarks Read current joint data from loaded Conve...
DLLAPI char *ER_STDCALL erGetTargetLocationNameVia(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Name of target Via location, in case of circular motion.
DLLAPI long ER_STDCALL erMath_mul_T_pos(double *po, DFRAME *T, double *pi)
Multiplication of a 3x1 position with a homogeneous 4x4 transformation matrices. po = T * pi...
DLLAPI long ER_STDCALL erSetTool(ER_HND er_hnd, DFRAME *tTw)
Set robot tool (TCP) data w.r.t. robots flange.
DLLAPI long ER_STDCALL erToolPathSetConveyorHandle(ER_TOOLPATH_HND er_tpth_hnd, ER_HND hnd_Conveyor=NULL)
Set conveyor handle belonging to tool path handle. The tool path handles the conveyor device as exter...
DLLAPI int ER_STDCALL erGeoMngr_CheckBoundingBoxCollision(DFRAME *T1, const double *bbox1, DFRAME *T2, const double *bbox2, double tolerance)
DLLAPI long ER_STDCALL erSET_CARTESIAN_POSITION_SPEED(ER_HND er_hnd, double speed_value)
Sets the speed for Cartesian motion. Opcode 133, Chapter 3.4.5, Page 3-75.
DLLAPI long ER_STDCALL erToolPathReset(ER_TOOLPATH_HND er_tpth_hnd)
Reset all tool path target locations. All target locations defined in tool path er_tpth_hnd are reset...
DLLAPI long ER_STDCALL erSET_JOINT_ACCELERATIONS(ER_HND er_hnd, long all_joint_flags, long joint_flags, double accel_percent, long accel_type)
Sets the joint accelerations expressed as percentage of the maximal joint acceleration. Opcode 135, Chapter 3.4.5, Page 3-77. Remarks If all_joint_flags is 1, the value in accel_percent is in [rad/s^2] for rotational joint type and in [m/s^2] for prismatic joint type. It is recommended to set all_joint_flags =0 and use joint_flags, where accel_percent is a percentage value. The maximum joint accelerations can be changed with erSetAqMax() and erGetAqMax(). The accel_type specifies the type of acceleration and can be one of the following values. 1: Acceleration, 2: Deceleration, 3: Acceleration and deceleration.
DLLAPI long ER_STDCALL erSetJointSolutions(ER_HND er_hnd, double *q_solutions, long *q_warnings)
Set all robot joint solutions. The kinematics joint data q_solutions are in units [m] for prismatic j...
DLLAPI long ER_STDCALL erSET_CONFIGURATION_CONTROL(ER_HND er_hnd, char *param_id, char *param_contents)
Allows the setting of controller-specific data for the control of robot configurations. Opcode 161, Chapter 3.4.4, Page 3-72 Function not supported Use function erSetConfig(), erGetConfig() to change the robots configuration.
DLLAPI long ER_STDCALL erSetExtTcpRobotBase(ER_HND er_hnd, DFRAME *bText, long use_ext_flange)
Set location of external TCP w.r.t robot base. Exeption: If use_ext_flange is set, the external TCP w.r.t is defined w.r.t. the (tip) flange of a positioner for example.
DLLAPI double *ER_STDCALL erGetMotionAttributes_flyby_speed_percent(ER_TARGET_ATTRIBUTES_HND hnd)
flyby by speed [%] for a target location In case of flyby by speed, the robot starts moving into the ...
DLLAPI void ER_STDCALL erSetCallBack_NotifyProc(TerNotifyProc Handler)
Define Callback function for notify messages The Kernel informs the host application about internel s...
DLLAPI size_t *ER_STDCALL erGeoMngr_GetGeometryObjPolygon(TErGeoHandle geometryHandle, int objidx, int index)
DLLAPI long ER_STDCALL erKernelInitialize(char *HostApplicationPath, char *Sold_To_ID, long mode=0)
Initializes the Kernel. After calling this initial functions all other kernel functions are available...
DLLAPI long ER_STDCALL erSELECT_POINT_ACCURACY(ER_HND er_hnd, long accuracy_type)
Selects a criterion for when a target is reached. Opcode 144, Chapter 3.4.6, Page 3-89 Function not s...
DLLAPI int ER_STDCALL erGeoMngr_FreeGeometry(ER_HND er_hnd, TErGeoHandle GeoHandle)
Free or delete a geometry.
DLLAPI long ER_STDCALL erGetJointFrameRobotBase(ER_HND er_hnd, long active_jnt_no, DFRAME *bTax)
Get location of active joint coorsys w.r.t robot base. Get the number of active joints with erGet_num...
DLLAPI long ER_STDCALL erGET_NEXT_TOOLPATH_STEP_INIT(ER_TOOLPATH_HND er_tpth_hnd, long cntrl=ER_MOP_GNTPS_CNTRL_INIT)
Initializes the interpolation through a complete tool path Parameter cntrl must be set to ER_MOP_GNTP...
DLLAPI ER_TARGET_LOCATION_HND ER_STDCALL erToolPathGetTargetLocationLast(ER_TOOLPATH_HND er_tpth_hnd)
Get the last &#39;target location handle&#39; in the tool path.
DLLAPI long ER_STDCALL erSELECT_TARGET_TYPE(ER_HND er_hnd, long target_type)
selects one of different types for the specification of targets. Opcode 121, Chapter 3...
DLLAPI TErTargetID ER_STDCALL erGET_CURRENT_TARGETID(ER_HND er_hnd)
Returns the TargetID of the motion in execution. Opcode 163, Chapter 3.4.6, Page 3-91.
DLLAPI ER_TARGET_ATTRIBUTES_HND ER_STDCALL erGetTargetLocationMotionAttributesHnd(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Handle for target attributes data Typical attributes belonging to a target location are: e...
DLLAPI long ER_STDCALL erGetJointFramePassiveNext(ER_HND er_hnd, long passive_jnt_no, DFRAME *T)
DLLAPI long ER_STDCALL erGetVqMax(ER_HND er_hnd, double *vq_max)
Get maximum of robot joint speeds. Robot joint speeds vq_max are in units [m/s] for prismatic joint t...
DLLAPI long ER_STDCALL erGET_CARTESIAN_POSITION_ACCELERATION(ER_HND er_hnd, double *accel_value, long accel_type)
Gets acceleration for cartesian motion [m/sec^2]. The accel_type specifies the type of acceleration a...
DLLAPI long *ER_STDCALL erGetMotionAttributes_flyby_on(ER_TARGET_ATTRIBUTES_HND hnd)
Rounding / flyby condition for a target location In case of flyby enabled, the robot moves through a ...
DLLAPI long ER_STDCALL erMath_mul_T_T_invT(DFRAME *To, DFRAME *Ti1, DFRAME *Ti2, DFRAME *Ti3)
Tripple multiplication of homogeneous 4x4 transformation matrices. To = Ti1 * Ti2 * inv(Ti3) Remarks ...
DLLAPI long ER_STDCALL erGetJointFramePassiveLast(ER_HND er_hnd, long passive_jnt_no, DFRAME *T)
Contains additional desired data for current interpolation step Usage with erGetCurrentStepData() aft...
DLLAPI long ER_STDCALL erSetAutoAccel(ER_HND er_hnd, long autoaccel)
Enables automatic calculation of acceleration depending on programmed speed. Using AutoAccel is a pro...
const int ER_COLL_FIRST_CONTACT
report first intersecting tri pair found, erColl_ChkCollision()
Definition: erk_capi_types.h:721
DLLAPI long ER_STDCALL erSetTargetLocation_Move_LIN(ER_TARGET_LOCATION_HND er_tarloc_hnd, double *CartPosVec, double speed_cp=0, double speed_ori=0, double override_speed=0, long flyby_on=-1, double *Tool=0, double *Base=0)
Move_LIN, continious path motion definition for target location Remarks Use erAddTargetLocation() to...
DLLAPI long ER_STDCALL erSwapToolPath(ER_TOOLPATH_HND er_tpth_hnd1, ER_TOOLPATH_HND er_tpth_hnd2)
Swap two tool pathes. Swaps the position of two tool path handles.
DLLAPI double *ER_STDCALL erGetMotionAttributes_ToolOffsetVec(ER_TARGET_ATTRIBUTES_HND hnd)
ToolOffset (TCP) for a target location Offset Transformation from TCP see inq_ToolOffsetIdx(), inq_ToolOffsetName()
DLLAPI long *ER_STDCALL erGetExtAxTrack_number_extax_used(ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND hnd)
Number of external axis used for Track/Slider see example GetExtAxTrackMotionHnd() ...
DLLAPI int ER_STDCALL erGeoMngr_GetGeometryCloneCount(TErGeoHandle geometryHandle)
DLLAPI long *ER_STDCALL erGetMotionAttributes_ToolIdx(ER_TARGET_ATTRIBUTES_HND hnd)
Idx for Tool for a target location see inq_ToolVec(), inq_ToolName() This ToolIdx could be useful whe...
DLLAPI ER_HND ER_STDCALL erConnectConveyorGetHND(ER_HND er_hnd)
Get robots connection handle between robot and conveyor. See also erConnectConveyor() ...
DLLAPI long ER_STDCALL erCONTINUE_MOTION(ER_HND er_hnd)
Continues a motion that was stopped with the erSTOP_MOTION() function. Opcode 152, Chapter 3.4.8, Page 3-102 See also erSTOP_MOTION(), erCANCEL_MOTION() Remarks After calling this function, the erGET_NEXT_STEP() should be called repeatedly in order to get the acceleration steps.
const long ER_SYNC_UNDEF
device synchronization not defined
Definition: erk_capi_types.h:346
DLLAPI long 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_...
DLLAPI int ER_STDCALL erGeoMngr_GetGeometryObjNumLines(TErGeoHandle geometryHandle, int objidx)
DLLAPI long ER_STDCALL CpyMoveJointTemplate(ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_MOVE_JOINT_HND hnd)
Copy move joint data to template data. The move joint data defined with move joint handle hnd are cop...
DLLAPI char *ER_STDCALL erGetMotionAttributes_extTcpOffsetName(ER_TARGET_ATTRIBUTES_HND hnd)
Name for external Tool/TCP offset data w.r.t. extTcpBase, extTcpWorld, for a target location see inq_...
DLLAPI long ER_STDCALL erKernelGetLicensePriority(int *license_priority)
Get license priority. Parameter license_priority is one of ER_LICENSE_PRIORITY_LMNGR, ER_LICENSE_PRIORITY_LOCAL If license_priority is not set, ER_LICENSE_PRIORITY_LMNGR is default setting, see erKernelSetLicensePriority()
DLLAPI long ER_STDCALL erGET_CARTESIAN_ORIENTATION_ACCELERATION(ER_HND er_hnd, long rotation_no, double *accel_ori_value, long accel_type)
Gets acceleration for the orientation during cartesian motion [m/sec^2]. The rotation_no should be 1...
DLLAPI long ER_STDCALL erSetVqMax(ER_HND er_hnd, double *vq_max)
Set maximum of robot joint speeds. Robot joint speeds vq_max are in units [m/s] for prismatic joint t...
DLLAPI long ER_STDCALL erSetJointDyn(ER_HND er_hnd, double q_dyn, long jnt_no)
Set a single actual robot joint data. The kinematics joint data q_dyn are in units [m] for prismatic ...
DLLAPI long ER_STDCALL erUnloadTool(ER_HND er_hnd)
Unload a kinematics tool. Unloads a kinematics tool givin by the unique kinematics handle...
DLLAPI long ER_STDCALL erGetAqMax(ER_HND er_hnd, double *aq_max)
Get maximum of robot joint accelerations. Robot joint accelerations aq_max are in units [m/s^2] for p...
unsigned int TErTargetID
unique Target identifier
Definition: erk_capi_types.h:190
DLLAPI void ER_STDCALL erSetCallBack_GetActualTravelRangesProc(TerGetActualTravelRangesProc Handler)
Define Callback function to calculate travel ranges by host application The Host application takes ca...
DLLAPI long ER_STDCALL erMath_Frame_Ident(DFRAME *T)
Set the homogeneous 4x4 transformation matrix T to identity. T = Ident A frame DFRAME is a homogeneou...
DLLAPI long ER_STDCALL erGetName(ER_HND er_hnd, char *name)
Get the name of the robot.
DLLAPI long ER_STDCALL erSetJointFramePassiveNext(ER_HND er_hnd, long passive_jnt_no, DFRAME *T)
DLLAPI TErTargetID *ER_STDCALL erGetMotionAttributes_target_id(ER_TARGET_ATTRIBUTES_HND hnd)
unique target ID of a target location
sets the robot model to a position according to the input data. Usage with erSET_INITIAL_POSITION() ...
Definition: erk_capi_types.h:363
DLLAPI long ER_STDCALL erConnectRobotGetSync(ER_HND er_hnd)
Get robots synchronization flag for synchronization between robot and slave robot. See also erConnectRobotSetSync()
unsigned int * ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND
unique External device definition for Conveyor
Definition: erk_capi_types.h:205
DLLAPI long ER_STDCALL erToolPathResetInitTrackMotion(ER_TOOLPATH_HND er_tpth_hnd, double *q_start=NULL)
Set initial joint start location for the TrackMotion. Remarks Read current joint data from loaded Tr...
DLLAPI long ER_STDCALL erSetExtAxPositionerIdx(ER_TARGET_LOCATION_HND er_tarloc_hnd, long extax_idx, double axis_value, double speed_value=0, long sync_type=ER_SYNC_UNDEF, ER_HND er_hnd_connect=0)
Set external axis values for Positioner/TurnTable for target location see example GetExtAxPositioner...
DLLAPI char *ER_STDCALL erGetInstructions_LeadInstructions(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Get LeadInstructions target instruction data for target location. For further explanations see GetIns...
DLLAPI long ER_STDCALL erGetTool(ER_HND er_hnd, DFRAME *tTw)
Get robot tool (TCP) data w.r.t. robots flange.
DLLAPI long ER_STDCALL erGetAxis_couplingA2A3(ER_HND er_hnd, long *axis_couplingA2A3)
Get robot axis coupling between axis 2 and 3 The axis coupling can be one of the following values...
DLLAPI long *ER_STDCALL erGetMotionAttributes_ToolOffsetIdx(ER_TARGET_ATTRIBUTES_HND hnd)
Idx for ToolOffset for a target location see inq_ToolOffsetVec(), inq_ToolOffsetName() This ToolOffse...
DLLAPI long ER_STDCALL erSetTargetLocation_Move_Joint(ER_TARGET_LOCATION_HND er_tarloc_hnd, double *CartPosVec, long configuration=0, long ptp_target_calculation_mode=ER_PTP_TARGET_CALC_MODE_UNDEF, double speed_percent=0, double override_speed=0, double *Tool=0, double *Base=0)
Move_Joint, full synchronized PTP, motion definition for target location Remarks Use erAddTargetLoca...
DLLAPI long ER_STDCALL erGetpJointMoveBase(ER_HND er_hnd, DFRAME *pjntTmb)
Get transformation from passive joint &#39;pjnt&#39; to the moveable base &#39;mb&#39;. If a kinematics base is movea...
DLLAPI long ER_STDCALL erGetTargetLocationIdx(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Index of target location.
DLLAPI long ER_STDCALL erGetJoints(ER_HND er_hnd, double *q_solut)
Get robot joint data. The kinematics joint data q_solut are in units [m] for prismatic joint type an...
DLLAPI long ER_STDCALL erGetJointFrameWorld(ER_HND er_hnd, long active_jnt_no, DFRAME *iTax)
Get location of active joint coorsys w.r.t innertia (world). Get the number of active joints with erG...
unsigned int * ER_TOOLPATH_HND
unique Tool path handle, created with erInitToolPath()
Definition: erk_capi_types.h:194
DLLAPI long ER_STDCALL erGetRobotBase(ER_HND er_hnd, DFRAME *iTb)
Get robot base location w.r.t. world.
DLLAPI long ER_STDCALL erSetCounter_weight(ER_HND er_hnd, long counter_weight)
Set robot counter weight The robot counter weight can be one of the following values. KIN_COUNTER_WEIGHT_NO=0, KIN_COUNTER_WEIGHT_YES =1 or KIN_COUNTER_WEIGHT_UNKNOWN =2 see also erGetCounter_weight()
DLLAPI long ER_STDCALL erGetSweMin(ER_HND er_hnd, double *swe_min)
Get fix minimum travel ranges. The kinematics travel ranges swe_min are in units [m] for prismatic jo...
DLLAPI int ER_STDCALL erGeoMngr_GetVersion()
GeoMngr Version.
DLLAPI const double *ER_STDCALL erGeoMngr_GetGeometryBBox(TErGeoHandle geometryHandle)
DLLAPI long ER_STDCALL erSELECT_DOMINANT_INTERPOLATION(ER_HND er_hnd, long dominant_int_type, long dominant_int_param=0)
Sets the interplation space defining the movement. Opcode 124, Chapter 3.4.4, Page 3-66 The parameter...
DLLAPI long ER_STDCALL erCANCEL_MOTION(ER_HND er_hnd)
Cancel a motion that was stopped with erSTOP_MOTION() function. Opcode 153, Chapter 3...
DLLAPI long ER_STDCALL erGetRobotBasetoFirstJoint(ER_HND er_hnd, DFRAME *T)
DLLAPI long ER_STDCALL erGetIDs(ER_HND er_hnd, long *kin_id, long *inv_id, long *inv_sub_id)
Get Kinematics ID of the robot. kin_id represents the kinematics ID. It can be one of the following v...
DLLAPI void ER_STDCALL erSetCallBack_LoadGeometryProc(TerLoadGeometryProc Handler)
Define Callback function to load a geometry The Host application is prompted to load a geometry...
DLLAPI long ER_STDCALL erGetRobotBaseTcp(ER_HND er_hnd, DFRAME *bTw)
Get robot tcp location w.r.t. robot base.
DLLAPI long ER_STDCALL erInvKinRobotBaseTip(ER_HND er_hnd, DFRAME *bTt)
Calculating the inverse kinematics transformation. The bTt is the location of the flange w...
DLLAPI double ER_STDCALL erGetMotionExec_trajectory_time(ER_TARGET_MOTION_EXEC_HND hnd)
Trajectory time [s], elapsed time to reach the target location, while interpolation trough the comple...
DLLAPI char *ER_STDCALL erGetMotionAttributes_ToolName(ER_TARGET_ATTRIBUTES_HND hnd)
Name for Tool for a target location see inq_ToolVec(), inq_ToolIdx() This ToolName could be useful wh...
DLLAPI long ER_STDCALL erGet_n_Kin(ER_HND er_hnd)
Get the number of loaded kinematics.
DLLAPI long ER_STDCALL erAddTargetLocation(ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_LOCATION_HND *er_tarloc_hnd)
Add a new target location to a tool path Remarks The new target location is reset to default values ...
DLLAPI long ER_STDCALL erGET_NEXT_STEP(ER_HND er_hnd, long output_format, NEXT_STEP_DATA *p_next_step_data, double time)
Returns the next interpolated position step the elapsed time and supplementary information like event...
DLLAPI long ER_STDCALL erSetTargetLocation_Move_Slew(ER_TARGET_LOCATION_HND er_tarloc_hnd, double *CartPosVec, long configuration=0, long ptp_target_calculation_mode=ER_PTP_TARGET_CALC_MODE_UNDEF, double speed_percent=0, double override_speed=0, double *Tool=0, double *Base=0)
Move_Slew, not synchronized PTP, motion definition for target location Remarks Use erAddTargetLocati...
DLLAPI long ER_STDCALL erConnectPositionerSetSync(ER_HND er_hnd, long connect_sync)
Set robots synchronization flag for synchronization between robot and positioner. The synchronization...
DLLAPI long ER_STDCALL erGetRobotBaseToMoveBase(ER_HND er_hnd, DFRAME *bTmb)
Get transformation from robot base &#39;b&#39; to the moveable base &#39;mb&#39;. If a kinematics base is moveable...
DLLAPI int ER_STDCALL erGeoMngr_GetNumGeometries(ER_HND er_hnd)
Get number of loaded geometries for specified device.
DLLAPI long ER_STDCALL erSetVxOriMax(ER_HND er_hnd, double vx_ori_max)
Set maximum cartesian orientation speed.
DLLAPI long ER_STDCALL erGetJointFrameWorld_passive(ER_HND er_hnd, long passive_jnt_no, DFRAME *iTax)
Get location of passive joint coorsys w.r.t innertia (world). Get the number of passive joints with e...
DLLAPI long ER_STDCALL erInvKinWorldTcp(ER_HND er_hnd, DFRAME *iTw)
Calculating the inverse kinematics transformation. The iTw is the location of the tcp w...
DLLAPI long ER_STDCALL erSET_ADVANCE_MOTION(ER_HND er_hnd, long Number_of_motion)
Defines the number of motions, the motion planner may run in advance of the interpolator (look_ahead)...
DLLAPI long ER_STDCALL erGetCounter_weight(ER_HND er_hnd, long *counter_weight)
Get robot counter weight The robot counter weight can be one of the following values. KIN_COUNTER_WEIGHT_NO=0, KIN_COUNTER_WEIGHT_YES =1 or KIN_COUNTER_WEIGHT_UNKNOWN =2 see also erSetCounter_weight()
DLLAPI long ER_STDCALL erSetSweMin(ER_HND er_hnd, double *swe_min)
Set fix minimum travel ranges. The kinematics travel ranges swe_min are in units [m] for prismatic jo...
unsigned int * Host_HND
unique Host handle given from Host, NULL per default, erInitKin()
Definition: erk_capi_types.h:188
DLLAPI long ER_STDCALL erSetTurn_value(ER_HND er_hnd, long *turn_value)
Set the turn value for each robot joint The turn value turn_value determine the desired Turn in the ...
DLLAPI long ER_STDCALL erSET_FLYBY_CRITERIA_PARAMETER(ER_HND er_hnd, long param_number, long joint_nr, double param_value)
Sets the value of a flyby parameter. Opcode 141, Chapter 3.4.6, Page 3-86 Function not supported ...
DLLAPI long ER_STDCALL erSET_JOINT_SPEEDS(ER_HND er_hnd, long all_joint_flags, long joint_flags, double speed_percent)
sets the joint speed expressed as percentage of the maximal joint speed. Opcode 131, Chapter 3.4.5, Page 3-74. Remarks If all_joint_flags is 1, the value in speed_percent is in [rad/s] for rotational joint type and in [m/s] for prismatic joint type. It is recommended to set all_joint_flags =0 and use joint_flags, where speed_percent is a percentage value. The maximum joint speeds can be changed with erSetVqMax() and erGetVqMax().
DLLAPI long *ER_STDCALL erGetMotionAttributes_extTcpWorldIdx(ER_TARGET_ATTRIBUTES_HND hnd)
Idx for external Tool (TCP) w.r.t. Robot World or flange of positioner, for a target location see inq...
DLLAPI long *ER_STDCALL erGetMotionAttributes_autoaccel(ER_TARGET_ATTRIBUTES_HND hnd)
Automatic calculation of acceleration depending on programmed speed for a target location Using AutoA...
DLLAPI long ER_STDCALL erSetConfig(ER_HND er_hnd, long config)
Set robot configuration A new robot configuration takes effect when calling the inverse kinematics tr...
TErGeoHandle(ER_STDCALL * TerLoadGeometryProc)(ER_HND ErHandle, LOAD_GEOMETRY_DATA *p_load_geometry_data)
Callback function type definition to load a geometry, erSetCallBack_LoadGeometryProc() ...
Definition: erk_capi_types.h:602
DLLAPI int ER_STDCALL erGeoMngr_GetGeometry(ER_HND er_hnd, int geometryIndex, LOAD_GEOMETRY_DATA *p_load_geometry_data, DFRAME *kinMat)
DLLAPI int ER_STDCALL erGeoMngr_SetGeometryIsCollided(TErGeoHandle geometryHandle, int isCollided)
const long ER_ROT_XYZ
Rotation Index: RotX*RotY*RotZ, EASY-ROB, Staeubli CS8, erMath_VecToFrameIdx(), erMath_FrameToVecIdx...
Definition: erk_capi_types.h:698
DLLAPI long ER_STDCALL erConnectPositionerGetSync(ER_HND er_hnd)
Get robots synchronization flag for synchronization between robot and positioner. See also erConnectP...
DLLAPI ER_TARGET_EXTAX_DEVICE_POSITIONER_HND ER_STDCALL erGetTargetLocationExtAxPositionerHnd(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Handle for external axis of a Positioner/TurnTable-Motion Typical data belonging to external axis da...
Collision results for query ER_COLL_QUERY_TYPE_DISTANCE, see erColl_GetResults_Distance() The followi...
Definition: erk_capi_types.h:759
DLLAPI long ER_STDCALL erGET_NEXT_TOOLPATH_STEP(ER_TOOLPATH_HND er_tpth_hnd, long cntrl, NEXT_STEP_DATA *p_next_step_data=NULL, double time=0)
Interpolation through a complete tool path Parameter cntrl is an individual bitwise-inclusive-OR oper...
DLLAPI ER_TARGET_INSTRUCTIONS_HND ER_STDCALL erGetTargetLocationInstructionsHnd(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Handle for target instruction data Remarks Instructions are individual command or information attach...
DLLAPI ER_HND ER_STDCALL erToolPathGetTrackMotionHandle(ER_TOOLPATH_HND er_tpth_hnd)
Get device track motion handle belonging to tool path handle.
DLLAPI long ER_STDCALL erTPth_PostProc(char *ApiPP_Dll_Name, int FctIdx, int FctSubIdx, ER_TOOLPATH_HND er_tpth_hnd, char *program_name, char *target_path=NULL, int pp_param=0, char *svalues=NULL)
Method for post processing, creating a robot program for a tool path An example Visual Studio Project...
DLLAPI long ER_STDCALL erSET_MOTION_FILTER(ER_HND er_hnd, long filter_factor)
defines the filter factor for smoothing velocity profiles of motions. Opcode 128, Chapter 3...
DLLAPI long *ER_STDCALL erGetExtAxConveyor_number_extax_used(ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND hnd)
Number of external axis used for Conveyor see example GetExtAxConveyorHnd()
DLLAPI double *ER_STDCALL erGeoMngr_GetGeometryObjPointNormal(TErGeoHandle geometryHandle, int objidx, int index)
DLLAPI double *ER_STDCALL erGetMoveCP_CartPosVec(ER_TARGET_MOVE_CP_HND hnd)
Cartesian position w.r.t. Base for CP move for target location Remarks Use for.
DLLAPI long ER_STDCALL erSET_OVERRIDE_SPEED(ER_HND er_hnd, double correction_value, long correction_type)
Sets correction values for scaling the programmed speed during program execution. Opcode 139...
Contains target data for about next move &quot;advance move&quot; This structure contains all required data for...
DLLAPI long ER_STDCALL erMath_mul_R_pos(double *po, DFRAME *R, double *pi)
Multiplication of a 3x1 position with the 3x3 orientation of a homogeneous 4x4 transformation matrice...
unsigned int * ER_TARGET_INSTRUCTIONS_HND
Instructions, individual information text.
Definition: erk_capi_types.h:197
Geometry data structure for callback function. Used when loading and updating robot geometries With c...
Definition: erk_capi_types.h:248
DLLAPI TErGeoHandle ER_STDCALL erGeoMngr_GetGeometryCloneHandle(TErGeoHandle geometryHandle)
unsigned int * ER_COLLISION_HND
unique Collision handle, created with erColl_BeginModel()
Definition: erk_capi_types.h:192
DLLAPI ER_TARGET_HEAD_HND ER_STDCALL erGetTargetLocationHeaderDataHnd(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Handle for target header data.
DLLAPI long ER_STDCALL erMath_mul_T_T(DFRAME *To, DFRAME *Ti1, DFRAME *Ti2)
Multiplication of two homogeneous 4x4 transformation matrices. To = Ti1 * Ti2 A frame DFRAME is a hom...
DLLAPI long ER_STDCALL erMath_invT(DFRAME *To, DFRAME *Ti)
Builds the inverse of a homogeneous 4x4 transformation matrix T. To = inv(Ti) = ( Ri&#39; ...
DLLAPI long ER_STDCALL erSET_CONVEYOR_POSITION(ER_HND er_hnd, long input_format, long conveyor_flags, double conveyor_pos)
Sends the conveyor position to the Kernel. Opcode 147, Chapter 3.4.7, Page 3-94 Function not supporte...
DLLAPI long ER_STDCALL erColl_AddTri(ER_COLLISION_HND er_coll_hnd, double *p1, double *p2, double *p3, long id)
Adds a triangle to a Model. call erColl_BeginModel() once to create a new unique model handle...
DLLAPI long ER_STDCALL erGetAxOriMax(ER_HND er_hnd, double *ax_ori_max)
Get maximum cartesian orientation acceleration.
DLLAPI double *ER_STDCALL erGetMotionAttributes_extTcpOffsetVec(ER_TARGET_ATTRIBUTES_HND hnd)
external Tool/TCP offset data w.r.t. extTcpBase, extTcpWorld, for a target location Transformation fr...
DLLAPI ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND ER_STDCALL erGetTargetLocationExtAxConveyorHnd(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Handle for external axis of a Conveyor-Motion Typical data belonging to external axis data are: numb...
DLLAPI const double *ER_STDCALL erGeoMngr_GetAxisBBox(ER_HND er_hnd, int axis_id)
DLLAPI ER_HND ER_STDCALL erToolPathGetConveyorHandle(ER_TOOLPATH_HND er_tpth_hnd)
Get device conveyor handle belonging to tool path handle.
DLLAPI ER_EXTAX_KIN_DATA *ER_STDCALL erGetExtAxPositioner_extax_data(ER_TARGET_EXTAX_DEVICE_POSITIONER_HND hnd, long extax_idx)
External axis values for Positioner/TurnTable Values ER_EXTAX_KIN_DATA are: .
DLLAPI long ER_STDCALL erGetTargetLocationNumber(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Number of target locations in a tool path.
DLLAPI long ER_STDCALL erGetJointDirections(ER_HND er_hnd, long *jnt_direction_active)
Get direction of active robot joints. A robot joint direction can be JNT_DIRECTION_X, JNT_DIRECTION_Y or JNT_DIRECTION_Z See also erGetJointSign(), erGetJointTypes()
unsigned int * ER_TARGET_MOVE_JOINT_HND
unique Target data for Joint Move handle
Definition: erk_capi_types.h:200
DLLAPI long ER_STDCALL erTargetLocationReset(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Reset Target location to default values Remarks The target location is marked as invalid...
DLLAPI long ER_STDCALL erColl_EndModel(ER_COLLISION_HND er_coll_hnd)
Stop building a Model.
DLLAPI size_t *ER_STDCALL erGeoMngr_GetGeometryObjLine(TErGeoHandle geometryHandle, int objidx, int index)
DLLAPI ER_TARGET_ATTRIBUTES_AUX_HND ER_STDCALL erGetTargetLocationMotionAttributesAuxHnd(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Handle for target attributes auxiliary data.
DLLAPI long *ER_STDCALL erGetMoveJoint_turn_value(ER_TARGET_MOVE_JOINT_HND hnd)
Turn value for each robot joint for joint move for target location The turn value determine the desir...
DLLAPI long ER_STDCALL erInvKinRobotBaseTcp(ER_HND er_hnd, DFRAME *bTw)
Calculating the inverse kinematics transformation. The bTw is the location of the tcp w...
DLLAPI long ER_STDCALL erGetInvKinSubID(ER_HND er_hnd, long *invkinsub_id)
Inverse kinematics Sub-ID for cRobot. .
DLLAPI long ER_STDCALL erSwapTargetLocation(ER_TARGET_LOCATION_HND er_tarloc_hnd1, ER_TARGET_LOCATION_HND er_tarloc_hnd2)
Swap the order of two target location in a tool path Remarks Both target location handle must be in ...
DLLAPI char *ER_STDCALL erGetMotionAttributes_ToolOffsetName(ER_TARGET_ATTRIBUTES_HND hnd)
Name for ToolOffset for a target location see inq_ToolOffsetVec(), inq_ToolOffsetIdx() This ToolOffse...
DLLAPI long ER_STDCALL CpyExtAxTrackMotionTemplate(ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND hnd)
Copy external axis track motion data to template data. The external axis track motion data defined wi...
DLLAPI long ER_STDCALL erGeoMngr_GetGeometryObjColorCode(TErGeoHandle geometryHandle, int objidx)
DLLAPI double *ER_STDCALL erGetMotionAttributes_ToolVec(ER_TARGET_ATTRIBUTES_HND hnd)
Tool (TCP) for a target location Transformation from Tip to TCP see inq_ToolIdx(), inq_ToolName()
DLLAPI long ER_STDCALL erGetAccSet(ER_HND er_hnd, double *acc, double *ramp)
Get lagging of accelerations. Using AccSet is a proper way to come close to real cycle times when the...
DLLAPI long ER_STDCALL erGetJointAttachDof_active(ER_HND er_hnd, long *jnt_attach_dof_active)
Get Attach-Dof of active robot joints. An active joint with chain type JNT_CHAIN_TYPE_CHAIN is attach...
DLLAPI long ER_STDCALL erSetTurn_offset(ER_HND er_hnd, double *turn_offset)
Set the turn offset for each robot joints The kinematics turn offset turn_offset are in units [m] for...
DLLAPI long ER_STDCALL erSET_OVERRIDE_ACCELERATION_EX(ER_HND er_hnd, ER_HND er_hnd_slave, double accel_override, double tcp_accel_max=0)
Sets override for scaling the programmed acceleration during program execution. If er_hnd_slave is NU...
DLLAPI long 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() Initi...
DLLAPI long ER_STDCALL erSetExtAxConveyorIdx(ER_TARGET_LOCATION_HND er_tarloc_hnd, long extax_idx, double axis_value, double speed_value=0, long sync_type=ER_SYNC_UNDEF, ER_HND er_hnd_connect=0)
Set external axis values for Conveyor for target location see example GetExtAxConveyorHnd() Remarks ...
unsigned int TErTrackingWindowID
unique TrackingWindow identifier
Definition: erk_capi_types.h:191
DLLAPI long ER_STDCALL erInsertTargetLocation(ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_LOCATION_HND *er_tarloc_hnd, ER_TARGET_LOCATION_HND er_tarloc_hnd_ref=NULL)
Insert a new target location to a tool path before an existing target location Remarks The new targe...
DLLAPI long ER_STDCALL erGetMotionExec_motion_success(ER_TARGET_MOTION_EXEC_HND hnd)
Motion success is true when the robot has reached the target location successfully Remarks ERK_CAPI_...
DLLAPI ER_COLLISION_HND *ER_STDCALL erGeoMngr_GetGeometryCollisionHandle(TErGeoHandle geometryHandle)
DLLAPI long 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_hn...
DLLAPI double *ER_STDCALL erGeoMngr_GetGeometryObjColor(TErGeoHandle geometryHandle, int objidx)
DLLAPI ER_EXTAX_KIN_DATA *ER_STDCALL erGetExtAxTrack_extax_data(ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND hnd, long extax_idx)
External axis values for Track/Slider Values ER_EXTAX_KIN_DATA are: .
DLLAPI long ER_STDCALL erGetVxMax(ER_HND er_hnd, double *vx_max)
Get maximum cartesian speed.
DLLAPI long ER_STDCALL erSetAxis_couplingA2A3(ER_HND er_hnd, long axis_couplingA2A3)
Set robot axis coupling between axis 2 and 3 The axis coupling can be one of the following values...
DLLAPI ER_TARGET_ATTRIBUTES_HND ER_STDCALL GetMotionAttributesTemplateHnd(ER_TOOLPATH_HND er_tpth_hnd)
Get attributes template data from tool path. Get the attributes template data belonging to the tool p...
DLLAPI long ER_STDCALL erColl_ChkCollision_res(ER_COLLISION_HND er_coll_hnd_1, DFRAME *iT_1, ER_COLLISION_HND er_coll_hnd_2, DFRAME *iT_2, long query_type=ER_COLL_QUERY_TYPE_COLLIDE, long contact_type=ER_COLL_FIRST_CONTACT, double rel_err=0, double abs_err=0, double tolerance=0, void *pres=NULL)
Perform the collision check of two Models. Collision results returned immediately by parameter pres c...
DLLAPI long ER_STDCALL erSetRobotBase(ER_HND er_hnd, DFRAME *iTb)
Set robot base location w.r.t. world.
DLLAPI long ER_STDCALL erSET_OVERRIDE_SPEED_EX(ER_HND er_hnd, ER_HND er_hnd_slave, double speed_override, double tcp_speed_max=0)
Sets override for scaling the programmed speed during program execution. If er_hnd_slave is NULL...
DLLAPI double *ER_STDCALL erGetMotionExec_ExtAxValues(ER_TARGET_MOTION_EXEC_HND hnd)
External axis values at target location, while interpolation trough the complete tool path...
DLLAPI long ER_STDCALL erSetSweMax(ER_HND er_hnd, double *swe_max)
Set fix maximum travel ranges. The kinematics travel ranges swe_max are in units [m] for prismatic jo...
DLLAPI double *ER_STDCALL erGetMoveCP_speed_cp(ER_TARGET_MOVE_CP_HND hnd)
Cartesian speed [m/s], for CP move for target location.
DLLAPI ER_TARGET_MOVE_CP_HND ER_STDCALL erGetTargetLocationMoveCPHnd(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Handle for target move CP data Typical data belonging to a move CP target location are: target_type...
DLLAPI long ER_STDCALL erGetJointChainTypes(ER_HND er_hnd, long *jnt_chain_type_active)
Get chain type of active robot joints. A robot chain type can be JNT_CHAIN_TYPE_CHAIN, JNT_CHAIN_TYPE_NO_CHAIN or JNT_CHAIN_TYPE_SEP_NO_CHAIN .
DLLAPI long ER_STDCALL erSELECT_MOTION_TYPE(ER_HND er_hnd, long motion_type)
Selects the motion type. Opcode 120, Chapter 3.4.4, Page 3-58 The motion_type can be one of the follo...
DLLAPI long ER_STDCALL erGetHomepos(ER_HND er_hnd, double *homepos)
Get robot joint homeposition. The kinematics joint homepos are in units [m] for prismatic joint type ...
DLLAPI long ER_STDCALL erDEFINE_EVENT(ER_HND er_hnd, long event_id, long target_id, double resolution, long type_of_event, double event_spec)
Defines an internal asynchronous event that is to be generated relative to position and/or time in th...
DLLAPI void ER_STDCALL erSetCallBack_FreeGeometryProc(TerFreeGeometryProc Handler)
Define Callback function to free Geometry The Host application is prompted to free a geometry...
DLLAPI long ER_STDCALL erMath_mul_invT_T_T(DFRAME *To, DFRAME *Ti1, DFRAME *Ti2, DFRAME *Ti3)
Tripple multiplication of homogeneous 4x4 transformation matrices. To = inv(Ti1) * Ti2 * Ti3 Remarks ...
DLLAPI long ER_STDCALL erGET_NEXT_TOOLPATH_STEP_TERMINATE(ER_TOOLPATH_HND er_tpth_hnd)
Terminates interpolation Remarks This method must be called after the interpolation of a tool path...
DLLAPI ER_TARGET_LOCATION_HND ER_STDCALL erGetTargetLocationNext(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Get next target location in a tool path.
long(ER_STDCALL * TerGetActualTravelRangesProc)(ER_HND ErHandle, Host_HND HostHandle, double *Joints, double *TravelRangeMin, double *TravelRangeMax)
Callback function type definition for user defined calculation of min./max. travel ranges in current ...
Definition: erk_capi_types.h:631
DLLAPI long ER_STDCALL erMath_AngleBetween(DFRAME *Ts, DFRAME *Te, double *angle, double *k=NULL)
Calculates the angle and the equivalent angle axis between two homogeneous 4x4 transformation matrice...
DLLAPI ER_TARGET_LOCATION_HND ER_STDCALL erGetTargetLocationFirst(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Get first target location in a tool path.
unsigned int * ER_TARGET_HEAD_HND
unique Header data handle
Definition: erk_capi_types.h:196
DLLAPI long ER_STDCALL erMath_DistBetween(DFRAME *Ts, DFRAME *Te, double *dist, double *dv=NULL)
Calculates the distance and direction between two homogeneous 4x4 transformation matrices. Translation from start frame Ts into end frame Te by the distance dist in direction vd A frame DFRAME is a homogeneous 4x4 transformation matrix.
DLLAPI double *ER_STDCALL erGetMotionAttributes_extTcpBaseVec(ER_TARGET_ATTRIBUTES_HND hnd)
external Tool (TCP) w.r.t. Robot Base or flange of positioner, for a target location Transformation f...
DLLAPI long ER_STDCALL erGetJointSign(ER_HND er_hnd, double *joint_sign)
Get sign of robot joints. A robot joint sign can be positive +1 or negative -1. See also erGetJointTy...
DLLAPI long ER_STDCALL erKernelGetLicense(char *hw_id)
Check license and supplies unique HardwareID or DongleID.
DLLAPI long ER_STDCALL erTPth_TBox_Fct(int FctIdx, int FctSubIdx, ER_TOOLPATH_HND er_tpth_hnd, int constraint_param, char *svalues=NULL)
Method for miscellaneous tool path calculations Requires DLL EasySimKernel_tboxx64.dll.
DLLAPI long ER_STDCALL CpyMotionAttributesTemplate(ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_ATTRIBUTES_HND hnd)
Copy attributes to template data. The attributes defined with attribute handle hnd are copied to the ...
DLLAPI long ER_STDCALL erGetCurrentStepData(ER_HND er_hnd, CURRENT_STEP_DATA *p_current_step_data)
Returns interpolation data for the current interpolated step Remarks After the next step data are ca...
DLLAPI long ER_STDCALL erGetWorldTip(ER_HND er_hnd, DFRAME *iTt)
Get robot tip location w.r.t. inertia (world) coorsys.
DLLAPI long ER_STDCALL erGetJointFrameActiveNext(ER_HND er_hnd, long active_jnt_no, DFRAME *T)
DLLAPI long ER_STDCALL erSetTargetLocation_Move_CIRC(ER_TARGET_LOCATION_HND er_tarloc_hnd, double *CartPosVecVia, double *CartPosVec, double speed_cp=0, double speed_ori=0, double override_speed=0, long flyby_on=-1, double *Tool=0, double *Base=0)
Move_CIRC, continious path motion definition for target location Remarks Use erAddTargetLocation() t...
DLLAPI long ER_STDCALL erGetSweMax_passive(ER_HND er_hnd, double *swe_max_passive)
Get fix maximum travel ranges from passive joints. The kinematics travel ranges swe_max_passive are i...
DLLAPI long ER_STDCALL erSetJointFrameActiveLast(ER_HND er_hnd, long active_jnt_no, DFRAME *T)
DLLAPI long ER_STDCALL erINITIALIZE(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 erInitKin() Initiali...
DLLAPI long ER_STDCALL erGetExtTcpWorld(ER_HND er_hnd, DFRAME *iText)
Get location of external TCP w.r.t inertia (world).
DLLAPI long ER_STDCALL erGetSweMinCalc(ER_HND er_hnd, double *swe_min_calc)
Get calculated minimum travel ranges. The kinematics calculated travel ranges swe_min_calc are in uni...
DLLAPI long ER_STDCALL erGetJointOffset(ER_HND er_hnd, double *joint_offset)
Get offset of robot joints. Robot joint offsets joint_offset are in units [m] for prismatic joint typ...
DLLAPI long ER_STDCALL erGetSpeedReductionEnable(ER_HND er_hnd, long *speed_reduction_enable)
Get speed reduction enable. If speed reduction is enabled, the robots TCP speed gets reduced (while m...
DLLAPI long ER_STDCALL erSetConveyorTrackingWindow(ER_TARGET_LOCATION_HND er_tarloc_hnd, long active, double up, double down, TErTrackingWindowID id_tw, char *name=NULL)
Activates and deactivates the boundaries for a Tracking Window. This function enables a tracking wind...
DLLAPI long *ER_STDCALL erGetExtAxConveyor_sync_type(ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND hnd)
Synchonization for Conveyor For a Conveyor motion, the synchonization can be one of ER_SYNC_ON...
DLLAPI long 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 callb...
DLLAPI long ER_STDCALL erColl_GetResults_Distance(ER_DistanceResult *er_dres)
Get Collision result for query ER_COLL_QUERY_TYPE_DISTANCE. Remarks Call erColl_ChkCollision() first...
DLLAPI long ER_STDCALL erConnectTrackMotionGetSync(ER_HND er_hnd)
Get robots synchronization flag for synchronization between robot and track motion. See also erConnectTrackMotionSetSync()
DLLAPI long ER_STDCALL erSetBaseWorld(ER_HND er_hnd, DFRAME *iTbase)
Set $BASE (wobj) w.r.t inertia (world). The $BASE frame has only effect when IPO_MODE_BASE is set in ...
DLLAPI ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND ER_STDCALL erGetTargetLocationExtAxTrackHnd(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Handle for external axis of a Track/Slider-Motion Typical data belonging to external axis data are: ...
DLLAPI long ER_STDCALL erColl_GetResults_Tolerance(ER_ToleranceResult *er_tres)
Get Collision result for query ER_COLL_QUERY_TYPE_TOLERANCE. Remarks Call erColl_ChkCollision() firs...
DLLAPI ER_HND ER_STDCALL erConnectRobotGetHND(ER_HND er_hnd)
Get robots connection handle between robot and slave robot. See also erConnectRobot() ...
DLLAPI long 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...
DLLAPI long ER_STDCALL erGetRobotBaseTip(ER_HND er_hnd, DFRAME *bTt)
Get robot tip (flange) location w.r.t. robot base.
unsigned int * ER_TARGET_MOTION_EXEC_HND
unique handle for motion execution data at target
Definition: erk_capi_types.h:202
long(ER_STDCALL * TerNotifyProc)(ER_HND ErHandle, Host_HND HostHandle, TErNotifyData *p_NotifyData, TErExtraData ExtraData)
Callback function type definition for notifications, erSetCallBack_NotifyProc()
Definition: erk_capi_types.h:641
DLLAPI ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND ER_STDCALL GetExtAxConveyorTemplate(ER_TOOLPATH_HND er_tpth_hnd)
Get external axis conveyor template data from tool path. Get the external axis conveyor template data...
DLLAPI ER_TARGET_LOCATION_HND ER_STDCALL erToolPathGetTargetLocationFirst(ER_TOOLPATH_HND er_tpth_hnd)
Get the first &#39;target location handle&#39; in the tool path.
DLLAPI long ER_STDCALL erGet_num_dofs(ER_HND er_hnd)
Get number of active robot joints.
DLLAPI long ER_STDCALL erMath_PxyzRxyzToFrame(double x, double y, double z, double Rx, double Ry, double Rz, DFRAME *T)
Converts an euler represented location with rotation index ER_ROT_XYZ into a frame. Location x, y, z, Rx, Ry, Rz are converted into a frame T A frame DFRAME is a homogeneous 4x4 transformation matrix. See also erMath_VecToFrameIdx(), erMath_FrameToVecIdx()
DLLAPI double *ER_STDCALL erGeoMngr_GetGeometryObjPoint(TErGeoHandle geometryHandle, int objidx, int index)
DLLAPI long ER_STDCALL erSetAxOriMax(ER_HND er_hnd, double ax_ori_max)
Set maximum cartesian orientation acceleration.
DLLAPI double *ER_STDCALL erMath_SetVec6(double *vec, double q1, double q2, double q3, double q4, double q5, double q6)
Cpy six values to a vector.
DLLAPI long ER_STDCALL erREVERSE_MOTION(ER_HND er_hnd, double distance)
Instructs to do a reverse motion. Opcode 130, Chapter 3.4.4, Page 3-70 The robot moves backwards alon...
DLLAPI long ER_STDCALL erKernelGetHardwareID(char *hw_id)
Supplies unique HardwareID or DongleID.
DLLAPI long *ER_STDCALL erGetMotionAttributes_enabled(ER_TARGET_ATTRIBUTES_HND hnd)
Enables/disables a target location If the target location is disabled, the trajectory interpolator wi...
DLLAPI long ER_STDCALL erGetJointChainTypes_passive(ER_HND er_hnd, long *jnt_chain_type_passive)
Get chain type of passive robot joints. A robot chain type can be JNT_CHAIN_TYPE_CHAIN, JNT_CHAIN_TYPE_NO_CHAIN or JNT_CHAIN_TYPE_SEP_NO_CHAIN .
DLLAPI long ER_STDCALL erUnloadTargetLocation(ER_TARGET_LOCATION_HND *er_tarloc_hnd)
Unload/delete a target location from a tool path Remarks Use erGetTargetLocationNumber() to receive ...
DLLAPI long *ER_STDCALL erGetMoveCP_interpolation_mode(ER_TARGET_MOVE_CP_HND hnd)
Orientation interpolation mode for CP move for target location The interpolation_mode is one of =1 on...
DLLAPI double *ER_STDCALL erGetMoveCP_accel_ori(ER_TARGET_MOVE_CP_HND hnd)
Cartesian orientation acceleration [rad/s^2], for CP move for target location.
DLLAPI long ER_STDCALL erSetSpeedReductionEnable(ER_HND er_hnd, long speed_reduction_enable)
Set speed reduction enable. If speed reduction is enabled, the robots TCP speed gets reduced (while m...
DLLAPI double *ER_STDCALL erGetMoveJoint_CartPosVec(ER_TARGET_MOVE_JOINT_HND hnd)
Cartesian position w.r.t. Base for joint move for target location Remarks Use for.
DLLAPI long ER_STDCALL erMath_mul_T_T_T(DFRAME *To, DFRAME *Ti1, DFRAME *Ti2, DFRAME *Ti3)
Tripple multiplication of homogeneous 4x4 transformation matrices. To = Ti1 * Ti2 * Ti3 A frame DFRAM...
DLLAPI long ER_STDCALL erMath_mul_invT_invT(DFRAME *To, DFRAME *Ti1, DFRAME *Ti2)
Multiplication of two homogeneous 4x4 transformation matrices. To = inv(Ti1) * inv(Ti2) Remarks inv(...
DLLAPI long *ER_STDCALL erGetMotionAttributes_BaseIdx(ER_TARGET_ATTRIBUTES_HND hnd)
Idx for program shift Base for a target location see inq_BaseVec(), inq_BaseName() This BaseIdx could...
DLLAPI long ER_STDCALL erGetExtTcpRobotBase(ER_HND er_hnd, DFRAME *bText)
Get location of external TCP w.r.t robot base.
DLLAPI void ER_STDCALL erKernelFree(void)
Free all internal Kernel data. Calling this function will delete all internal Kernel data After calli...
DLLAPI long ER_STDCALL erSET_MOTION_TIME(ER_HND er_hnd, double time_value)
Specifies the motion time for the next motion. Opcode 156, Chapter 3.4.5, Page 3-81.
long(ER_STDCALL * TerGrpSyncProc)(ER_HND ErHandle, Host_HND HostHandle, TErGrpSyncData *p_GrpSyncData)
Callback function type definition group synchronization, erSetCallBack_GrpSyncProc() ...
Definition: erk_capi_types.h:650
unsigned int * ER_TARGET_ATTRIBUTES_AUX_HND
unique Auxiliary motion attributes handle
Definition: erk_capi_types.h:198
DLLAPI char *ER_STDCALL erToolPathName(ER_TOOLPATH_HND er_tpth_hnd)
Device Handle belonging to tool path.
DLLAPI long ER_STDCALL erSetExtAxTrackIdx(ER_TARGET_LOCATION_HND er_tarloc_hnd, long extax_idx, double axis_value, double speed_value=0, long sync_type=ER_SYNC_UNDEF, ER_HND er_hnd_connect=0)
Set external axis values for Track/Slider for target location see example GetExtAxTrackMotionHnd() R...
DLLAPI long ER_STDCALL erGetMoveBasepJointIdx(ER_HND er_hnd, long *move_base_pjointidx)
Gets passive joint idx representing the moveable base. If a kinematics base is moveable, the move_base_pjointidx gives the index [1..number of passive joints] of the passive joints representing the moveable base. Otherwise it is 0, see erGetMoveBaseMode(), erGetpJointMoveBase()