EASY-ROBâ„¢ Kernel  v8.603
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 - 2022
8 
9  Date: AUG 2022
10  Version: 8.603
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  29-nov-2021 - SAN -> v8.308 License.enc
82  23-mar-2022 - SAN -> v8.602 PreRelease
83  03-aug-2022 - SAN -> v8.602 Patch erk_AutoPath*() c-functions added
84  09-aug-2022 - SAN -> v8.603 PreRelease
85 ------------------------------------------------------------------------------------------ */
86 
87 #ifndef _er_kernel_main_h
88 #define _er_kernel_main_h
89 
90 #include "erk_capi_types.h"
91 
92 #ifdef __cplusplus
93 extern "C" {
94 #endif
95 
96 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
97 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
98 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
99 // Administrative Kernel Functions, Initialization etc.
100 // class ERK_CAPI_ADMIN
101 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
102 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
103 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
104 #pragma region region_erk_init_license
105 
110 
119 DLLAPI long ER_STDCALL erKernelSetLicensePriority(int license_priority);
120 
128 DLLAPI long ER_STDCALL erKernelGetLicensePriority(int *license_priority);
129 
137 DLLAPI long ER_STDCALL erKernelSetLicenseFile(char *license_file);
138 
146 DLLAPI long ER_STDCALL erKernelAddLicenseFile(char *license_file);
147 
154 DLLAPI long ER_STDCALL erKernelGetLicenseFile(char *license_file);
155 
181 DLLAPI long ER_STDCALL erKernelInitialize(char *HostApplicationPath, char *Sold_To_ID, long mode=0);
182 
183 #pragma endregion region_erk_init_license
184 
185 #pragma region region_erk_admin
186 
192 DLLAPI void ER_STDCALL erKernelFree(void);
193 
199 DLLAPI long ER_STDCALL erKernelGetLicense(char *hw_id);
200 
206 DLLAPI long ER_STDCALL erKernelGetHardwareID(char *hw_id);
207 
213 DLLAPI long ER_STDCALL erKernelGetOptions(char *opt);
214 
221 
222 #pragma endregion region_erk_admin
223 
224 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
225 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
226 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
227 // Funktionen zum Aufnehmen der Call-Back Funktionen
228 // class ERK_CAPI_CALLBACKS
229 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
230 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
231 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
232 #pragma region region_erk_callbacks
233 
234 /* AddToHostLog
235  Fügt dem Log der Hostanwendung einen Eintrag hinzu, oder gibt eine Statusmeldung in der
236  Statuszeile aus.
237 */
243 
244 /* Enable/Disable
245  AddToHostLog messages
246 */
266 
267 /* HostLoadGeometry
268  Fordert die Hostanwendung auf eine Geometrie aus einer Datei zu laden.
269 
270  ErHandle: Handle der Kinematik, der die Geometrie zugeordnet werden soll.
271  GeoHandle: Handle auf eine eventuell schon zuvor geladene Geomtrie der Kinematik
272  Funktioniert derzeit nicht und muss 0 sein.
273  Scaling: Skalierungsfactor mit dem die Geomtrie skaliert werden soll.
274  GeoMat: Eine Transformation zur Lagekorrektur der Geometrie.
275  FileName: Name der Datei, die geladen werden soll. Derzeit wird ein vollständiger Pfad erwartet.
276 
277  Returns: Handle auf die geladene Geomtrie. Im Fehlerfall wird 0 zurückgeliefert
278 */
285 
286 /* HostUpdateGeometry
287  Fordert die Hostanwendung auf die Kinematiktransformation der Geometrie zu aktualisieren.
288 
289  ErHandle: Handle der Kinematik, der die Geometrie zugeordnet werden soll.
290  GeoHandle: Handle auf die Geomtrie, wie von "HostLoadGeometry" geliefert.
291  KinMat: Die neue Transformation.
292 
293  Returns: Im Fehlerfall 1, ansonsten 0
294 */
301 
302 /* HostFreeGeometry
303  Fordert die Hostanwendung die Geometrie freizugeben.
304 
305  ErHandle: Handle der Kinematik, der die Geometrie zugeordnet werden soll.
306  GeoHandle: Handle auf die Geomtrie, wie von "HostLoadGeometry" geliefert.
307 
308  Returns: Im Fehlerfall 1, ansonsten 0
309 */
316 
317 /* HostGetActualTravelRanges
318  Fordert die Hostanwendung die Travel Ranges zu berechnen.
319 
320  ErHandle: Handle der Kinematik, der die Travel Ranges zugeordnet werden soll.
321 
322  Returns: Im Fehlerfall 1, ansonsten 0
323 */
330 /* HostNotify
331  Gibt Meldung an die Hostanwendung.
332 */
339 
340 /* HostGrpSync
341  GrpSync IO Hostanwendung.
342 */
348 #pragma endregion region_erk_callbacks
349 
350 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
351 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
352 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
353 // class ERK_CAPI_DEVICES
354 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
355 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
356 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
357 
358 #pragma region region_erk_devices
359 
360 /* erInitKin
361  Erzeugt ein Roboter Handle
362  Return 0-OK, 1-Error
363  siehe auch erINITIALIZE
364 */
375 DLLAPI long ER_STDCALL erInitKin(ER_HND *er_hnd, Host_HND host_hnd=NULL);
376 
377 /* erUnloadKin
378  Unload Robot Handle
379  Return 0-OK, 1-Error
380 */
390 DLLAPI long ER_STDCALL erUnloadKin(ER_HND *er_hnd);
391 
392 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
393 //
394 // erConnect* NEW_050402
395 //
396 // erConnectPositioner erConnectPositionerSetSync erConnectPositionerGetSync
397 // erConnectConveyor erConnectConveyorSetSync erConnectConveyorGetSync
398 // erConnectTrackMotion erConnectTrackMotionSetSync erConnectTrackMotionGetSync
399 // erConnectRobot erConnectRobotSetSync erConnectRobotGetSync
400 //
401 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
402 /* erConnectPositioner
403  Connects Positioner Kinematik mit dem Handle 'er_hnd_connect' zum Roboter mit dem Handle 'er_hnd'
404  Return 0-OK, 1-Error
405 */
431 DLLAPI long ER_STDCALL erConnectPositioner(ER_HND er_hnd, ER_HND er_hnd_connect);
439 
440 /* erConnectPositionerSetSync
441  Setzt Sync Flag der Positioner Kinematik
442  Return 0-OK, 1-Error
443 */
453 DLLAPI long ER_STDCALL erConnectPositionerSetSync(ER_HND er_hnd, long connect_sync);
454 
455 /* erConnectPositionerGetSync
456  Liest Sync Flag der Positioner Kinematik
457  Return -1-Error, ER_SYNC_UNDEF, ER_SYNC_OFF, ER_SYNC_ON
458 */
468 
469 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
470 /* erConnectConveyor
471  Connects Conveyor Kinematik mit dem Handle 'er_hnd_connect' zum Roboter mit dem Handle 'er_hnd'
472  Return 0-OK, 1-Error
473 */
499 DLLAPI long ER_STDCALL erConnectConveyor(ER_HND er_hnd, ER_HND er_hnd_connect);
507 
508 /* erConnectConveyorSetSync
509  Setzt Sync Flag der Conveyor Kinematik
510  Return 0-OK, 1-Error
511 */
521 DLLAPI long ER_STDCALL erConnectConveyorSetSync(ER_HND er_hnd, long connect_sync);
522 
523 /* erConnectConveyorGetSync
524  Liest Sync Flag der Conveyor Kinematik
525  Return -1-Error, ER_SYNC_UNDEF, ER_SYNC_OFF, ER_SYNC_ON
526 */
536 
537 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
538 /* erConnectTrackMotion
539  Connects Track Kinematik mit dem Handle 'er_hnd_connect' zum Roboter mit dem Handle 'er_hnd'
540  Return 0-OK, 1-Error
541 */
567 DLLAPI long ER_STDCALL erConnectTrackMotion(ER_HND er_hnd, ER_HND er_hnd_connect);
575 
576 /* erConnectTrackMotionSetSync
577  Setzt Sync Flag der TrackMotion Kinematik
578  Return 0-OK, 1-Error
579 */
589 DLLAPI long ER_STDCALL erConnectTrackMotionSetSync(ER_HND er_hnd, long connect_sync);
590 /* erConnectTrackMotionGetSync
591  Liest Sync Flag der TrackMotion Kinematik
592  Return -1-Error, ER_SYNC_UNDEF, ER_SYNC_OFF, ER_SYNC_ON, ER_SYNC_CONVEYOR
593 */
604 
605 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
606 /* erConnectRobot
607  Connects Robot Kinematik mit dem Handle 'er_hnd_connect' zum Roboter mit dem Handle 'er_hnd'
608  Return 0-OK, 1-Error
609 */
635 DLLAPI long ER_STDCALL erConnectRobot(ER_HND er_hnd, ER_HND er_hnd_connect);
643 
644 /* erConnectRobotSetSync
645  Setzt Sync Flag der Robot Kinematik
646  Return 0-OK, 1-Error
647 */
657 DLLAPI long ER_STDCALL erConnectRobotSetSync(ER_HND er_hnd, long connect_sync);
658 /* erConnectRobotGetSync
659  Liest Sync Flag der Robot Kinematik
660  Return -1-Error, ER_SYNC_UNDEF, ER_SYNC_OFF, ER_SYNC_ON
661 */
671 
672 /* erUnloadTool
673  Loescht Tool GeoHandle und setzt Tool auf Ident
674  Important:
675  Damit die TCP Position stimmt, muss ein rob_kin_update() folgen
676  Return 0-OK, 1-Error
677 */
687 DLLAPI long ER_STDCALL erUnloadTool(ER_HND er_hnd);
688 
689 /* erLoadKin
690  Load an easy-rob robot file with tool
691  Return 0-OK, 1-Error oder Abort
692 */
704 DLLAPI long ER_STDCALL erLoadKin(ER_HND er_hnd,char *fln_rob);
705 
706 /* erLoadTool
707  Load an easy-rob tool file
708  Return 0-OK, 1-Error oder Abort
709 */
717 DLLAPI long ER_STDCALL erLoadTool(ER_HND er_hnd,char *fln_tool);
718 
719 /* erGet_n_Kin
720  Return Number of loaded Robots "m_n_rob_kin"
721 */
727 DLLAPI long ER_STDCALL erGet_n_Kin(ER_HND er_hnd);
728 
729 /* erGet_n_Kin_IR
730  Return Number of loaded Robots with more than 3 joints and inverse kinematics "m_n_rob_kin_ir"
731 */
738 
739 /* erGetName
740  Name of Robot
741  Return 0-OK, 1-Error oder Abort
742 */
748 DLLAPI long ER_STDCALL erGetName(ER_HND er_hnd,char *name);
749 
750 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
751 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
752 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
753 // Robot Kinematics
754 // class ERK_CAPI_ROB_KIN
755 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
756 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
757 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
758 
759 /* erGetIDs
760  Kinematik ID - kinematischer Typ
761  RRRRRR_id =1; // Manutec
762  TTTRRR_id =2; // Portal
763  RRRRRR_bl_id =3; // ABB back link
764  UNIV_ROB_id =10; // Universelle Koordinaten
765  DH_id =11; // DH Koordinaten
766  inv_id - ID fuer inverse Kineamtik
767  inv_sub_id - Sub ID fuer inverse Kineamtik
768  Return 0-OK, 1-Error oder Abort
769 */
782 DLLAPI long ER_STDCALL erGetIDs(ER_HND er_hnd,long *kin_id,long *inv_id, long *inv_sub_id);
783 
784 /* erGet_num_dofs
785  Return Number of Robot active joints
786 */
793 
794 /* erGet_num_dofs_passive
795  Return Number of Robot passive joints
796 */
803 
804 /* erGetJointTypes
805  gets type of active robot joints 0-Rot 1-Trans
806  Return 0-OK, 1-Error oder Abort
807 */
816 DLLAPI long ER_STDCALL erGetJointTypes(ER_HND er_hnd, long *jnt_type_active);
817 
818 /* erGetJointTypes_passive
819  gets type of passive robot joints 0-Rot 1-Trans
820  Return 0-OK, 1-Error oder Abort
821 */
830 DLLAPI long ER_STDCALL erGetJointTypes_passive(ER_HND er_hnd, long *jnt_type_passive);
831 
832 /* erGetJointDirections
833  gets direction of active robot joints 1-JNT_DIRECTION_X, 2-JNT_DIRECTION_Y, 3-JNT_DIRECTION_Z
834  Return 0-OK, 1-Error oder Abort
835 */
844 DLLAPI long ER_STDCALL erGetJointDirections(ER_HND er_hnd, long *jnt_direction_active);
845 
846 /* erGetJointDirections_passive
847  gets type direction of passive robot joints 1-JNT_DIRECTION_X, 2-JNT_DIRECTION_Y, 3-JNT_DIRECTION_Z
848  Return 0-OK, 1-Error oder Abort
849 */
858 DLLAPI long ER_STDCALL erGetJointDirections_passive(ER_HND er_hnd, long *jnt_direction_passive);
859 
860 /* erGetJointChainTypes
861  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
862  Return 0-OK, 1-Error or Abort
863 */
871 DLLAPI long ER_STDCALL erGetJointChainTypes(ER_HND er_hnd, long *jnt_chain_type_active);
872 
873 /* erGetJointChainTypes_passive
874  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
875  Return 0-OK, 1-Error or Abort
876 */
884 DLLAPI long ER_STDCALL erGetJointChainTypes_passive(ER_HND er_hnd, long *jnt_chain_type_passive);
885 
886 /* erGetJointAttachDof_active
887  gets Attach-Dof of active robot joints
888  Return 0-OK, 1-Error or Abort
889 */
899 DLLAPI long ER_STDCALL erGetJointAttachDof_active(ER_HND er_hnd, long *jnt_attach_dof_active);
900 
901 /* erGetJointAttachDof_passive
902  gets Attach-Dof of passive robot joints
903  Return 0-OK, 1-Error or Abort
904 */
913 DLLAPI long ER_STDCALL erGetJointAttachDof_passive(ER_HND er_hnd, long *jnt_attach_dof_passive);
914 
915 /* erGetMoveBaseMode
916  gets moveable base mode 0-Robot base is fix (default), 1-Robot base is moveable
917  Return 0-OK, 1-Error oder Abort
918 */
928 DLLAPI long ER_STDCALL erGetMoveBaseMode(ER_HND er_hnd,long *move_base_mode);
929 
930 /* erGetMoveBasepJointIdx
931  gets passive joint idx representing the moveable base
932  0-Robot base is fix (default)
933  n-index of passive joint representing the moveable base
934  Return 0-OK, 1-Error oder Abort
935 */
944 DLLAPI long ER_STDCALL erGetMoveBasepJointIdx(ER_HND er_hnd,long *move_base_pjointidx);
945 
946 /* erGetpJointMoveBase
947  get transformation from passive joint 'pjnt' to the moveable base 'mb'
948  Return 0-OK, 1-Error oder Abort
949 */
958 DLLAPI long ER_STDCALL erGetpJointMoveBase(ER_HND er_hnd,DFRAME *pjntTmb);
959 
960 /* erGetRobotBaseToMoveBase
961  get transformation from robot base 'b' to the moveable base 'mb'
962  bTmb is Ident, if moveable base is fix
963  Return 0-OK, 1-Error oder Abort
964 */
974 
975 /* erSetJoints
976  Set Robot joints
977  Return 0-OK, 1-Error oder Abort
978 */
987 DLLAPI long ER_STDCALL erSetJoints(ER_HND er_hnd,double *q_solut);
988 
989 /* erSetJoint
990  Set Robot joint
991  Return 0-OK, 1-Error oder Abort
992 */
1003 DLLAPI long ER_STDCALL erSetJoint(ER_HND er_hnd,double q_solut, long jnt_no);
1004 
1005 /* erGetJoints
1006  Get current (active) Robot joints
1007  Return 0-OK, 1-Error oder Abort
1008 */
1020 DLLAPI long ER_STDCALL erGetJoints(ER_HND er_hnd,double *q_solut);
1021 
1022 /* erGetJointSolutions
1023  Get all (active) Robot joints solutions
1024  Return 0-OK, 1-Error oder Abort
1025 */
1074 DLLAPI long ER_STDCALL erGetJointSolutions(ER_HND er_hnd,double *q_solutions, long *q_warnings);
1075 
1076 /* erGetJointSpeeds
1077  Get current (active) Robot joint speeds
1078  Return 0-OK, 1-Error oder Abort
1079 */
1089 DLLAPI long ER_STDCALL erGetJointSpeeds(ER_HND er_hnd,double *v_solut);
1090 
1091 /* erGetJointAccels
1092  Get current (active) Robot joint accels
1093  Return 0-OK, 1-Error oder Abort
1094 */
1104 DLLAPI long ER_STDCALL erGetJointAccels(ER_HND er_hnd,double *a_solut);
1105 
1106 /* erGetJoints_passive
1107  Get current passive Robot joints
1108 */
1118 DLLAPI long ER_STDCALL erGetJoints_passive(ER_HND er_hnd,double *q_passive);
1119 
1120 /* erSetConfig
1121  Set Robot configuration
1122 */
1135 DLLAPI long ER_STDCALL erSetConfig(ER_HND er_hnd, long config);
1136 
1137 /* erGetConfig
1138  Set Robot configuration
1139 */
1148 DLLAPI long ER_STDCALL erGetConfig(ER_HND er_hnd, long *config);
1149 
1150 /* erFindConfig
1151  Find current Robot configuration
1152 */
1163 DLLAPI long ER_STDCALL erFindConfig(ER_HND er_hnd, long *config);
1164 
1165 /* erGetNumConfigs
1166  Get Number of Robot configurations
1167 */
1174 DLLAPI long ER_STDCALL erGetNumConfigs(ER_HND er_hnd, long *num_configs);
1175 
1176 /* erInvKinRobotBaseTip
1177  Inverse bTt is Robot base to Tip
1178  Return:
1179  Return code for inverse kinematics, INV_WARN_*
1180 */
1195 
1196 /* erInvKinWorldTip
1197  Inverse iTt is World to Tip
1198  Return:
1199  Return code for inverse kinematics, INV_WARN_*
1200 */
1214 DLLAPI long ER_STDCALL erInvKinWorldTip(ER_HND er_hnd,DFRAME *iTt);
1215 
1216 /* erInvKinRobotBaseTcp
1217  Inverse bTt is Robot base to Tcp
1218  Return:
1219  Return code for inverse kinematics, INV_WARN_*
1220 */
1235 
1236 /* erInvKinWorldTcp
1237  Inverse iTt is World to Tcp
1238  Return:
1239  Return code for inverse kinematics, INV_WARN_*
1240 */
1254 DLLAPI long ER_STDCALL erInvKinWorldTcp(ER_HND er_hnd,DFRAME *iTw);
1255 
1256 /* erSetTool
1257  Set Tool Tip to Tcp
1258 */
1265 DLLAPI long ER_STDCALL erSetTool(ER_HND er_hnd,DFRAME *tTw);
1266 /* erGetTool
1267  Get Tool Tip to Tcp
1268 */
1282 DLLAPI long ER_STDCALL erGetTool(ER_HND er_hnd,DFRAME *tTw);
1283 
1284 /* erGetToolFix
1285  Get Tool Tip to fix Tcp, without Tool Offset
1286 */
1303 DLLAPI long ER_STDCALL erGetToolFix(ER_HND er_hnd, DFRAME *tTwfix);
1304 
1305 /* erSetToolOffset
1306  Set Tool Offset Tcp' to Tcp
1307 */
1314 DLLAPI long ER_STDCALL erSetToolOffset(ER_HND er_hnd, DFRAME *wTwo);
1315 /* erGetToolOffset
1316  Get Tool Offset Tcp' to Tcp
1317 */
1349 DLLAPI long ER_STDCALL erGetToolOffset(ER_HND er_hnd, DFRAME *wTwo);
1350 
1351 /* erSetBaseRobotBase
1352  Set Base w.r.t. RobotBase
1353 */
1362 DLLAPI long ER_STDCALL erSetBaseRobotBase(ER_HND er_hnd,DFRAME *bTbase);
1363 
1364 /* erGetBaseRobotBase
1365  Get Base w.r.t. RobotBase
1366 */
1375 DLLAPI long ER_STDCALL erGetBaseRobotBase(ER_HND er_hnd,DFRAME *bTbase);
1376 
1377 /* erSetBaseWorld
1378  Set Base w.r.t. World
1379 */
1388 DLLAPI long ER_STDCALL erSetBaseWorld(ER_HND er_hnd,DFRAME *iTbase);
1389 
1390 /* erGetBaseWorld
1391  Get Base w.r.t. World
1392 */
1401 DLLAPI long ER_STDCALL erGetBaseWorld(ER_HND er_hnd,DFRAME *iTbase);
1402 
1403 /* erSetRobotBase
1404  Set RobotBase, World to Robot base
1405 */
1412 DLLAPI long ER_STDCALL erSetRobotBase(ER_HND er_hnd,DFRAME *iTb);
1413 
1414 /* erGetRobotBase
1415  Get RobotBase, World to Robot base
1416 */
1430 DLLAPI long ER_STDCALL erGetRobotBase(ER_HND er_hnd,DFRAME *iTb);
1431 
1432 /* erGetRobotBaseTip
1433  Get Robot Tip w.r.t. Robot base
1434 */
1441 DLLAPI long ER_STDCALL erGetRobotBaseTip(ER_HND er_hnd,DFRAME *bTt);
1442 /* erGetRobotBaseTcp
1443  Get Robot Tcp w.r.t. Robot base
1444 */
1451 DLLAPI long ER_STDCALL erGetRobotBaseTcp(ER_HND er_hnd,DFRAME *bTw);
1452 
1453 /* erGetWorldTip
1454  Get Robot Tip w.r.t. World
1455 */
1462 DLLAPI long ER_STDCALL erGetWorldTip(ER_HND er_hnd,DFRAME *iTt);
1463 
1464 /* erGetWorldTcp
1465  Get Robot Tcp w.r.t. World
1466 */
1473 DLLAPI long ER_STDCALL erGetWorldTcp(ER_HND er_hnd,DFRAME *iTw);
1474 
1475 /* erUpdateKin
1476  Update the complete kinematic
1477 */
1486 DLLAPI long ER_STDCALL erUpdateKin(ER_HND er_hnd);
1487 
1488 /* erGetJointFrameRobotBase
1489  Transformation from RobotBase to (active) Robot Joint
1490  Return 0-OK, 1-Error oder Abort
1491 */
1500 DLLAPI long ER_STDCALL erGetJointFrameRobotBase(ER_HND er_hnd,long active_jnt_no,DFRAME *bTax);
1501 
1502 /* erGetJointFrameRobotBase_passive
1503  Transformation from RobotBase to passive Robot Joint
1504  Return 0-OK, 1-Error oder Abort
1505 */
1514 DLLAPI long ER_STDCALL erGetJointFrameRobotBase_passive(ER_HND er_hnd,long passive_jnt_no,DFRAME *bTax);
1515 
1516 /* erGetJointFrameWorld
1517  Transformation from World to (active) Robot Joint
1518  Return 0-OK, 1-Error oder Abort
1519 */
1528 DLLAPI long ER_STDCALL erGetJointFrameWorld(ER_HND er_hnd,long active_jnt_no,DFRAME *iTax);
1529 
1530 /* erGetJointFrameWorld_passive
1531  Transformation from World to passive Robot Joint
1532  Return 0-OK, 1-Error oder Abort
1533 */
1542 DLLAPI long ER_STDCALL erGetJointFrameWorld_passive(ER_HND er_hnd,long passive_jnt_no,DFRAME *iTax);
1543 
1544 /* erSetExtTcpRobotBase
1545  Set external Tcp w.r.t Robot Base
1546  Return 0-OK, 1-Error oder Abort
1547  Ausnahme: Beim Positioner ist der external Tcp w.r.t flange des positioners
1548 */
1557 DLLAPI long ER_STDCALL erSetExtTcpRobotBase(ER_HND er_hnd,DFRAME *bText, long use_ext_flange);
1558 
1559 /* erGetExtTcpRobotBase
1560  Get external Tcp w.r.t. Robot Base
1561  Return 0-OK, 1-Error oder Abort
1562 */
1569 DLLAPI long ER_STDCALL erGetExtTcpRobotBase(ER_HND er_hnd,DFRAME *bText);
1570 
1571 /* erSetExtTcpWorld
1572  Set external Tcp w.r.t world
1573  Return 0-OK, 1-Error oder Abort
1574 */
1581 DLLAPI long ER_STDCALL erSetExtTcpWorld(ER_HND er_hnd,DFRAME *iText);
1582 
1583 /* erGetExtTcpWorld
1584  Get external Tcp w.r.t. world
1585  Return 0-OK, 1-Error oder Abort
1586 */
1593 DLLAPI long ER_STDCALL erGetExtTcpWorld(ER_HND er_hnd,DFRAME *iText);
1594 
1595 /* erSetExtTcpMode
1596  Set ExtTcpMode 0-IPO_MODE_BASE (Werk ZEUG fuehrend), 1-IPO_MODE_TOOL (Werk STUECK fuehren)
1597  Return 0-OK, 1-Error oder Abort
1598 */
1606 DLLAPI long ER_STDCALL erSetExtTcpMode(ER_HND er_hnd,long ext_tcp_mode);
1607 
1608 /* erGetExtTcpMode
1609  Get ExtTcpMode 0-IPO_MODE_BASE (Werk ZEUG fuehrend), 1-IPO_MODE_TOOL (Werk STUECK fuehren)
1610  Return 0-OK, 1-Error oder Abort
1611 */
1619 DLLAPI long ER_STDCALL erGetExtTcpMode(ER_HND er_hnd,long *ext_tcp_mode);
1620 
1621 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1622 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1623 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1624 // Robot Kinematics API
1625 // class ERK_CAPI_ROB_KIN_API
1626 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1627 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1628 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1629 
1630 /* erGetInvKinID
1631  Inverse kinematics ID for cRobot
1632  Return 0-OK, 1-Error oder Abort
1633 */
1640 DLLAPI long ER_STDCALL erGetInvKinID(ER_HND er_hnd, long *invkin_id);
1641 
1642 /* erGetInvKinSubID
1643  Inverse kinematics Sub-ID for cRobot
1644  Return 0-OK, 1-Error oder Abort
1645 */
1652 DLLAPI long ER_STDCALL erGetInvKinSubID(ER_HND er_hnd, long *invkinsub_id);
1653 
1670 DLLAPI long ER_STDCALL erSetJointSolutions(ER_HND er_hnd, double *q_solutions, long *q_warnings);
1671 
1682 DLLAPI long ER_STDCALL erSetJointDyn(ER_HND er_hnd, double q_dyn, long jnt_no);
1683 
1685 DLLAPI long ER_STDCALL erGetJointFrameActiveNext(ER_HND er_hnd, long active_jnt_no, DFRAME *T);
1686 DLLAPI long ER_STDCALL erSetJointFrameActiveNext(ER_HND er_hnd, long active_jnt_no, DFRAME *T);
1687 DLLAPI long ER_STDCALL erGetJointFrameActiveLast(ER_HND er_hnd, long active_jnt_no, DFRAME *T);
1688 DLLAPI long ER_STDCALL erSetJointFrameActiveLast(ER_HND er_hnd, long active_jnt_no, DFRAME *T);
1689 
1690 DLLAPI long ER_STDCALL erGetJointFramePassiveNext(ER_HND er_hnd, long passive_jnt_no, DFRAME *T);
1691 DLLAPI long ER_STDCALL erSetJointFramePassiveNext(ER_HND er_hnd, long passive_jnt_no, DFRAME *T);
1692 DLLAPI long ER_STDCALL erGetJointFramePassiveLast(ER_HND er_hnd, long passive_jnt_no, DFRAME *T);
1693 DLLAPI long ER_STDCALL erSetJointFramePassiveLast(ER_HND er_hnd, long passive_jnt_no, DFRAME *T);
1695 
1696 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1697 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1698 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1699 // Robot Attributes
1700 // class ERK_CAPI_ROB_ATRIBUTES
1701 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1702 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1703 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1704 
1705 
1706 /* erSetHomepos
1707  Set Robot Home position
1708 */
1718 DLLAPI long ER_STDCALL erSetHomepos(ER_HND er_hnd,double *homepos);
1719 
1720 /* erGetHomepos
1721  Get Robot Home position
1722 */
1732 DLLAPI long ER_STDCALL erGetHomepos(ER_HND er_hnd,double *homepos);
1733 
1734 /* erSetSweMin
1735  Set Robot min. SWE Switch
1736 */
1746 DLLAPI long ER_STDCALL erSetSweMin(ER_HND er_hnd,double *swe_min);
1747 
1748 /* erGetSweMin
1749  Get min. SWE Switch
1750 */
1760 DLLAPI long ER_STDCALL erGetSweMin(ER_HND er_hnd,double *swe_min);
1761 
1762 /* erGetSweMinCalc
1763  Get min. calculated SWE Switch
1764 */
1775 DLLAPI long ER_STDCALL erGetSweMinCalc(ER_HND er_hnd,double *swe_min_calc);
1776 
1777 /* erSetSweMax
1778  Set max. SWE Switch
1779 */
1789 DLLAPI long ER_STDCALL erSetSweMax(ER_HND er_hnd,double *swe_max);
1790 
1791 /* erGetSweMax
1792  Get max. SWE Switch
1793 */
1803 DLLAPI long ER_STDCALL erGetSweMax(ER_HND er_hnd,double *swe_max);
1804 /* erGetSweMaxCalc
1805  Get max. calculated SWE Switch
1806 */
1817 DLLAPI long ER_STDCALL erGetSweMaxCalc(ER_HND er_hnd,double *swe_max_calc);
1818 
1819 /* erGetSweMinMaxCalc
1820  Get min. and max. calculated SWE Switches
1821 */
1833 DLLAPI long ER_STDCALL erGetSweMinMaxCalc(ER_HND er_hnd,double *swe_min_calc,double *swe_max_calc);
1834 
1842 DLLAPI long ER_STDCALL erGetSweCalcMode(ER_HND er_hnd,long *swe_calc_mode);
1843 
1844 /* erSetSweMin_passive
1845  Set Robot min. SWE Switch for passive joints
1846 */
1856 DLLAPI long ER_STDCALL erSetSweMin_passive(ER_HND er_hnd, double *swe_min_passive);
1857 /* erGetSweMin_passive
1858  Get min. SWE Switch from passive joints
1859 */
1869 DLLAPI long ER_STDCALL erGetSweMin_passive(ER_HND er_hnd, double *swe_min_passive);
1870 
1871 /* erSetSweMax_passive
1872  Set Robot max. SWE Switch for passive joints
1873 */
1883 DLLAPI long ER_STDCALL erSetSweMax_passive(ER_HND er_hnd, double *swe_max_passive);
1884 /* erGetSweMax_passive
1885  Get max. SWE Switch from passive joints
1886 */
1896 DLLAPI long ER_STDCALL erGetSweMax_passive(ER_HND er_hnd, double *swe_max_passive);
1897 
1898 /* erGetConfigName
1899  Name of robot configuration
1900  Return 0-OK, 1-Error oder Abort
1901 */
1909 DLLAPI long ER_STDCALL erGetConfigName(ER_HND er_hnd, long config_idx, char *config_name);
1910 
1911 /* erGetJointName
1912  Name of active robot joint
1913  Return 0-OK, 1-Error oder Abort
1914 */
1921 DLLAPI long ER_STDCALL erGetJointName(ER_HND er_hnd, long active_jnt_no, char *jnt_name);
1922 
1923 /* erGetJointName_passive
1924  Name of passive robot joint
1925  Return 0-OK, 1-Error oder Abort
1926 */
1933 DLLAPI long ER_STDCALL erGetJointName_passive(ER_HND er_hnd, long passive_jnt_no, char *jnt_name_passive);
1934 
1935 
1936 /* erSetJointSign
1937  Set Joint Directions
1938 */
1946 DLLAPI long ER_STDCALL erSetJointSign(ER_HND er_hnd,double *joint_sign); // NEW_050324
1947 
1948 /* erGetJointSign
1949  Get Joint Sign
1950 */
1959 DLLAPI long ER_STDCALL erGetJointSign(ER_HND er_hnd,double *joint_sign); // NEW_050324
1960 
1961 /* erSetJointOffset
1962  Set Joint Offsets
1963 */
1971 DLLAPI long ER_STDCALL erSetJointOffset(ER_HND er_hnd,double *joint_offset); // NEW_050324
1972 
1973 /* erGetJointOffset
1974  Get Joint Offsets
1975 */
1983 DLLAPI long ER_STDCALL erGetJointOffset(ER_HND er_hnd,double *joint_offset); // NEW_050324
1984 
1985 /* erSetVqMax
1986  Set max. joint speed [rad/s,m/s]
1987 */
1995 DLLAPI long ER_STDCALL erSetVqMax(ER_HND er_hnd,double *vq_max);
1996 
1997 /* erGetVqMax
1998  Get max. joint speed [rad/s,m/s]
1999 */
2007 DLLAPI long ER_STDCALL erGetVqMax(ER_HND er_hnd,double *vq_max);
2008 
2009 /* erSetAqMax
2010  Set max. joint acceleration [rad/s^2,m/s^2]
2011 */
2019 DLLAPI long ER_STDCALL erSetAqMax(ER_HND er_hnd,double *aq_max);
2020 
2021 /* erGetAqMax
2022  Get max. joint acceleration [rad/s^2,m/s^2]
2023 */
2031 DLLAPI long ER_STDCALL erGetAqMax(ER_HND er_hnd,double *aq_max);
2032 
2033 /* erSetVxMax
2034  Set max. cartesian speed [m/s]
2035 */
2042 DLLAPI long ER_STDCALL erSetVxMax(ER_HND er_hnd,double vx_max);
2043 
2044 /* erGetVxMax
2045  Get max. cartesian speed [m/s]
2046 */
2053 DLLAPI long ER_STDCALL erGetVxMax(ER_HND er_hnd,double *vx_max);
2054 
2055 /* erSetVxOriMax
2056  Set max. cartesian orientation speed [rad/s]
2057 */
2064 DLLAPI long ER_STDCALL erSetVxOriMax(ER_HND er_hnd,double vx_ori_max);
2065 
2066 /* erGetVxOriMax
2067  Get max. cartesian orientation orientation speed [rad/s]
2068 */
2075 DLLAPI long ER_STDCALL erGetVxOriMax(ER_HND er_hnd,double *vx_ori_max);
2076 
2077 /* erSetAxMax
2078  Set max. cartesian acceleration [m/s^2]
2079 */
2086 DLLAPI long ER_STDCALL erSetAxMax(ER_HND er_hnd,double ax_max);
2087 
2088 /* erGetAxMax
2089  Get max. cartesian acceleration [m/s^2]
2090 */
2097 DLLAPI long ER_STDCALL erGetAxMax(ER_HND er_hnd,double *ax_max);
2098 
2099 /* erSetAxOriMax
2100  Set max. cartesian orientation acceleration [rad/s^2]
2101 */
2109 DLLAPI long ER_STDCALL erSetAxOriMax(ER_HND er_hnd,double ax_ori_max);
2110 /* erGetAxOriMax
2111  Get max. cartesian orientation acceleration [rad/s^2]
2112 */
2119 DLLAPI long ER_STDCALL erGetAxOriMax(ER_HND er_hnd,double *ax_ori_max);
2120 
2121 /* erGetBackLink obsolete -> use erGetBacklink(...)
2122  Get Back Link returns robot back link information
2123  *backlink = 0-KIN_BACK_LINK_NO | 1-KIN_BACK_LINK_YES | 2-KIN_BACK_LINK_UNKNOWN
2124  Return 0-OK, 1-Error oder Abort
2125 */
2128 DLLAPI long ER_STDCALL erGetBackLink(ER_HND er_hnd,long *backlink); // obsolete -> use erGetBacklink(...)
2129 
2130 /* erSetBacklink
2131  Set Backlink extended attribute
2132 */
2142 DLLAPI long ER_STDCALL erSetBacklink(ER_HND er_hnd,long backlink);
2143 
2144 /* erGetBacklink
2145  Get Backlink extended attribute
2146 */
2156 DLLAPI long ER_STDCALL erGetBacklink(ER_HND er_hnd,long *backlink);
2157 
2158 /* erSetAxis_couplingA2A3
2159  Set Axis_couplingA2A3 extended attribute
2160 */
2170 DLLAPI long ER_STDCALL erSetAxis_couplingA2A3(ER_HND er_hnd,long axis_couplingA2A3);
2171 
2172 /* erGetAxis_couplingA2A3
2173  Get Axis_couplingA2A3 extended attribute
2174 */
2184 DLLAPI long ER_STDCALL erGetAxis_couplingA2A3(ER_HND er_hnd,long *axis_couplingA2A3);
2185 
2186 /* erSetCounter_weight
2187  Set Counter_weight extended attribute
2188 */
2198 DLLAPI long ER_STDCALL erSetCounter_weight(ER_HND er_hnd,long counter_weight);
2199 
2200 /* erGetCounter_weight
2201  Get Counter_weight extended attribute
2202 */
2212 DLLAPI long ER_STDCALL erGetCounter_weight(ER_HND er_hnd,long *counter_weight);
2213 
2214 /* erSetTurn_interval
2215  Set Turn_interval [rad,m]
2216 */
2227 DLLAPI long ER_STDCALL erSetTurn_interval(ER_HND er_hnd,double *turn_interval);
2228 
2229 /* erGetTurn_interval
2230  Get Turn_interval [rad,m]
2231 */
2242 DLLAPI long ER_STDCALL erGetTurn_interval(ER_HND er_hnd,double *turn_interval);
2243 
2244 /* erSetTurn_offset
2245  Set Turn_offset [rad,m]
2246 */
2257 DLLAPI long ER_STDCALL erSetTurn_offset(ER_HND er_hnd,double *turn_offset);
2258 
2259 /* erGetTurn_offset
2260  Get Turn_offset [rad,m]
2261 */
2272 DLLAPI long ER_STDCALL erGetTurn_offset(ER_HND er_hnd,double *turn_offset);
2273 
2274 /* erSetTurn_value
2275  Set Turn_value, will set turn_enable
2276 */
2289 DLLAPI long ER_STDCALL erSetTurn_value(ER_HND er_hnd,long *turn_value);
2290 
2291 /* erGetTurn_value
2292  Get Turn_value
2293 */
2304 DLLAPI long ER_STDCALL erGetTurn_value(ER_HND er_hnd,long *turn_value);
2305 
2306 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2307 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2308 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2309 // MotionPlanner
2310 // class ERK_CAPI_MOP
2311 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2312 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2313 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2314 
2315 /* erINITIALIZE
2316  Erzeugt ein Roboter Handle
2317  Opcode 101, Chapter 3.4.1, Page 3-26
2318  Return 0-OK, 1-Error
2319  entspricht erInitKin()
2320 */
2330 DLLAPI long ER_STDCALL erINITIALIZE (ER_HND *er_hnd, Host_HND host_hnd=NULL);
2331 
2332 /* erRESET
2333  Definition: Resets an instance of a robot to an initial state
2334  Opcode 102, Chapter 3.4.1, Page 3-29
2335  Return 0-OK, 1-Error
2336 */
2358 DLLAPI long ER_STDCALL erRESET(ER_HND er_hnd);
2359 
2360 /* erTERMINATE
2361  Loescht Roboter Handle
2362  Definition: Terminates an instance of a robot of the Kernel
2363  Opcode 103, Chapter 3.4.1, Page 3-30
2364  Return 0-OK, 1-Error
2365  see erUnloadKin()
2366 */
2374 DLLAPI long ER_STDCALL erTERMINATE(ER_HND *er_hnd);
2375 
2376 /* erSET_INITIAL_POSITION
2377  sets the robot model to a position according to the input data
2378  Opcode 116, Chapter 3.4.3, Page 3-50
2379  Return 0-OK, 1-Error
2380 */
2390 DLLAPI long ER_STDCALL erSET_INITIAL_POSITION(ER_HND er_hnd, INITIAL_POSITION_DATA *p_initial_position_data);
2391 
2392 /*erSELECT_TRACKING
2393  Definition: Selects the Tracking On or Off in the Kernel
2394  Opcode 146, Chapter 3.4.7, Page 3-93
2395  Return 0-OK, 1-Error, -1- not supported
2396 */
2408 DLLAPI long ER_STDCALL erSELECT_TRACKING(ER_HND er_hnd, long conveyor_flags);
2409 
2410 /*erSET_CONVEYOR_POSITION
2411  Definition: Sends the conveyor position to the Kernel
2412  Opcode 147, Chapter 3.4.7, Page 3-94
2413  Return 0-OK, 1-Error, -1- not supported
2414 */
2430 DLLAPI long ER_STDCALL erSET_CONVEYOR_POSITION(ER_HND er_hnd, long input_format, long conveyor_flags, double conveyor_pos);
2431 
2432 /*erDEFINE_EVENT
2433  Definition: Defines an internal asynchronous event that is to be generated relative to position and/or time in the Kernel
2434  Opcode 148, Chapter 3.4.8, Page 3-96
2435  Return 0-OK, 1-Error, -1- not supported
2436 */
2450 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);
2451 
2452 /*erCANCEL_EVENT
2453  Definition: This function makes it possible to cancel an event previously defined in the Kernel by the erDEFINE_EVENT() function
2454  Opcode 149, Chapter 3.4.8, Page 3-99
2455  Return 0-OK, 1-Error, -1- not supported
2456 */
2466 DLLAPI long ER_STDCALL erCANCEL_EVENT(ER_HND er_hnd, long event_id);
2467 
2468 /*erGET_EVENT
2469  Definition: This function gets information about an internal asynchronous event that occurred in the Kernel
2470  Opcode 150, Chapter 3.4.8, Page 3-100
2471  Return 0-OK, 1-Error, -1- not supported
2472 */
2482 DLLAPI long ER_STDCALL erGET_EVENT(ER_HND er_hnd, long event_nr);
2483 
2484 /*erGET_MESSAGE
2485  Definition: Gives information about controller messages that occurred
2486  Opcode 154, Chapter 3.4.9, Page 3-104
2487  Return 0-OK, 1-Error, -1- not supported
2488 */
2499 DLLAPI long ER_STDCALL erGET_MESSAGE(ER_HND er_hnd, long message_number);
2500 
2501 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2502 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2503 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2504 // MotionPlanner
2505 // class ERK_CAPI_MOP_DATA
2506 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2507 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2508 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2509 
2510 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2511 // Tracking Window
2512 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2513 /* erSetTrackingWindow
2514  Aktiviert/Deaktiviert das Tracking Window und gibt den Trackingbereich [Up..Down] an.
2515  Return 0-OK, 1-Error
2516 */
2536 DLLAPI long ER_STDCALL erSetTrackingWindow(ER_HND er_hnd, long active, double up, double down, TErTrackingWindowID id_tw, char *name=NULL);
2537 
2538 /* erSetconveyorStartCondition
2539  tx0 - Offsetposition in x-Rtg. bzgl. Conveyorflanch
2540  Return 0-OK, 1-Error
2541 */
2551 DLLAPI long ER_STDCALL erSetconveyorStartCondition(ER_HND er_hnd, double tx0);
2552 
2585 DLLAPI long ER_STDCALL erSetEvents_DOUT(ER_HND er_hnd, int idx = 1, long io_value = ER_EVENT_BOOL_UNDEF, char *io_name = 0, long strig_type = ER_EVENT_TRIGGER_OFF, double strig_time = 0, double strig_dist = 0, long ttrig_type = ER_EVENT_TRIGGER_OFF, double ttrig_time = 0, double ttrig_dist = 0);
2586 
2617 DLLAPI long ER_STDCALL erSetEvents_DIN(ER_HND er_hnd, int idx = 1, long io_value = ER_EVENT_BOOL_UNDEF, char *io_name = 0, long leadcond_type = ER_EVENT_CONDITION_UNDEF, double leadcond_value = 0, long lagcond_type = ER_EVENT_CONDITION_UNDEF, double lagcond_value = 0);
2618 
2619 //
2620 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2621 
2622 /* erSetSpeedReductionEnable
2623 */
2635 DLLAPI long ER_STDCALL erSetSpeedReductionEnable(ER_HND er_hnd,long speed_reduction_enable);
2636 
2637 /* erGetSpeedReductionEnable
2638 */
2650 DLLAPI long ER_STDCALL erGetSpeedReductionEnable(ER_HND er_hnd,long *speed_reduction_enable);
2651 
2652 /*erSELECT_MOTION_TYPE
2653  motion_type, ER_JOINT = 1, ER_LIN = 2, ER_SLEW = 3, ER_CIRC = 4
2654  Opcode 120, Chapter 3.4.4, Page 3-58
2655 */
2666 DLLAPI long ER_STDCALL erSELECT_MOTION_TYPE(ER_HND er_hnd, long motion_type);
2667 
2668 /*erSELECT_TARGET_TYPE
2669  Definition: selects one of different types for the specification of targets
2670  Opcode 121, Chapter 3.4.4, Page 3-59
2671  Return 0-OK, 1-Error
2672 
2673  Currently supported:
2674  0 - absolute w.r.t. object frame
2675  9 - single axis motion
2676 */
2688 DLLAPI long ER_STDCALL erSELECT_TARGET_TYPE(ER_HND er_hnd, long target_type);
2689 
2690 /*erSELECT_TRAJECTORY_MODE
2691  Definition: Selects on or off for the trajectory mode
2692  Opcode 122, Chapter 3.4.4, Page 3-62
2693  Return 0-OK, 1-Error, -1-not supported
2694 */
2704 DLLAPI long ER_STDCALL erSELECT_TRAJECTORY_MODE(ER_HND er_hnd, long trajectory_on);
2705 
2706 /*erSET_ADVANCE_MOTION
2707  Definition: defines the number of motions, the motion planner may run in advance of the interpolator (look_ahead)
2708  Opcode 127, Chapter 3.4.4, Page 3-67
2709 */
2717 DLLAPI long ER_STDCALL erSET_ADVANCE_MOTION(ER_HND er_hnd, long Number_of_motion);
2718 /*erSET_MOTION_FILTER
2719  Definition: defines the filter factor for smoothing velocity profiles of motions
2720  Opcode 128, Chapter 3.4.4, Page 3-68
2721 */
2730 DLLAPI long ER_STDCALL erSET_MOTION_FILTER(ER_HND er_hnd, long filter_factor);
2731 
2732 /*erREVERSE_MOTION
2733  Definition: Instructs to do a reverse motion
2734  Opcode 130, Chapter 3.4.4, Page 3-70
2735  Return 0-OK, 1-Error, -1-not supported
2736 */
2749 DLLAPI long ER_STDCALL erREVERSE_MOTION(ER_HND er_hnd, double distance );
2750 
2751 /*erSET_PAYLOAD_PARAMETER
2752  Definition: Allows specifying payloads at different locations on the robot.
2753  It has to be supported when the payload influences the motion planning.
2754  E.g. the load by a tool on the flange may be specified
2755  Opcode 160, Chapter 3.4.4, Page 3-71
2756  Return 0-OK, 1-Error, -1-not supported
2757 */
2773 DLLAPI long ER_STDCALL erSET_PAYLOAD_PARAMETER(ER_HND er_hnd, long storage, char *frame_id, long param_number, double param_value);
2774 
2775 /*erSET_CONFIGURATION_CONTROL
2776  Definition: Allows the setting of controller-specific data for the control of robot configurations
2777  Opcode 161, Chapter 3.4.4, Page 3-72
2778  Return 0-OK, 1-Error, -1-not supported
2779 */
2791 DLLAPI long ER_STDCALL erSET_CONFIGURATION_CONTROL(ER_HND er_hnd, char *param_id, char *param_contents);
2792 
2793 /*erSET_OVERRIDE_SPEED
2794  Definition: Sets correction values for scaling the programmed speed during program execution
2795  Opcode 139, Chapter 3.4.5, Page 3-82
2796  Return 0-OK, 1-Error, -1-not supported
2797 */
2811 DLLAPI long ER_STDCALL erSET_OVERRIDE_SPEED(ER_HND er_hnd, double correction_value, long correction_type);
2812 
2813 /*erSET_OVERRIDE_ACCELERATION
2814  Definition: Sets correction values for scaling the robot acceleration
2815  Opcode 155, Chapter 3.4.5, Page 3-83
2816  Return 0-OK, 1-Error, -1-not supported
2817 */
2834 DLLAPI long ER_STDCALL erSET_OVERRIDE_ACCELERATION(ER_HND er_hnd, double correction_value, long accel_type, long correction_type);
2835 
2836 /*erSET_OVERRIDE_SPEED_EX
2837  Definition: Sets override for scaling the programmed speed during program execution
2838  Return 0-OK, 1-Error, -1-not supported
2839 */
2853 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);
2854 
2855 /*erSET_OVERRIDE_ACCELERATION_EX
2856  Definition: Sets override for scaling the programmed acceleration during program execution
2857  Return 0-OK, 1-Error, -1-not supported
2858 */
2872 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);
2873 
2874 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2875 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2876 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2877 // MotionPlanner
2878 // class ERK_CAPI_MOP_PATH
2879 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2880 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2881 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2882 
2883 /* erSetAutoAccel
2884  Enables automatic calculation of acceleration
2885  depending on programmed speed
2886  ON = 7 – Calculation for PTP, POS and ORI
2887  POS = 1 – Calculation for motions for Position
2888  ORI = 2 – Calculation for motions for Orientation
2889  AX = 4 – Calculation for PTP motions
2890  OFF = 0 – Calculation deactivated
2891 */
2908 DLLAPI long ER_STDCALL erSetAutoAccel(ER_HND er_hnd,long autoaccel);
2909 
2910 /* erGetAutoAccel
2911  Get status for automatic calculation of acceleration
2912  depending on programmed speed
2913  ON = 7 – Calculation for PTP, POS and ORI
2914  POS = 1 – Calculation for motions for Position
2915  ORI = 2 – Calculation for motions for Orientation
2916  AX = 4 – Calculation for PTP motions
2917  OFF = 0 – Calculation deactivated
2918 */
2935 DLLAPI long ER_STDCALL erGetAutoAccel(ER_HND er_hnd,long *autoaccel);
2936 
2937 /* erSetAccSet
2938  Set lagging of accelerations.
2939  The arguments Acc and Ramp are given in percentage values in the range 20% to 100%
2940  Acc: Acceleration and Deceleration as percentage value of normal values
2941  Ramp: Change of Acceleration and Deceleration as percentage value of normal values
2942 */
2954 DLLAPI long ER_STDCALL erSetAccSet(ER_HND er_hnd,double acc,double ramp);
2955 
2956 /* erGetAccSet
2957  Get current lagging of accelerations.
2958  The arguments Acc and Ramp are given in percentage values in the range 20% to 100%
2959  Acc: Acceleration and Deceleration as percentage value of normal values
2960  Ramp: Change of Acceleration and Deceleration as percentage value of normal values
2961 */
2973 DLLAPI long ER_STDCALL erGetAccSet(ER_HND er_hnd,double *acc,double *ramp);
2974 
2975 /* erSET_INTERPOLATION_TIME
2976  sets the interpolation time in [ms]
2977  Opcode 119, Chapter 3.4.3, Page 3-56
2978  Return 0-OK, 1-Error
2979 */
2989 DLLAPI long ER_STDCALL erSET_INTERPOLATION_TIME(ER_HND er_hnd, double InterpolationTime);
2990 
2991 
2992 /*erSELECT_ORIENTATION_INTERPOLATION_MODE
2993 NEW_041112
2994 */
3005 DLLAPI long ER_STDCALL erSELECT_ORIENTATION_INTERPOLATION_MODE(ER_HND er_hnd, long interpolation_mode, long ori_const);
3006 
3007 /*erSELECT_CIRCULAR_ORIENTATION_INTERPOLATION_MODE
3008 NEW_070122
3009  Definition:
3010  selects the circular orientation interpolation mode
3011  circ_orientation_interpolation_mode:
3012  0: use Start- and Target Orientation
3013  1: use Start-, Via- and Target Orientation, default
3014  2: use Start-, Via- and Target Orientation, hereby the robot reaches the orientation in Via Point
3015  3: Tangential in Abhängigkeit der Orientierung im StartPunkt
3016  4: Constant, Fix
3017  Return 0-OK, 1-Error
3018 */
3028 DLLAPI long ER_STDCALL erSELECT_CIRCULAR_ORIENTATION_INTERPOLATION_MODE(ER_HND er_hnd, long circ_orientation_interpolation_mode);
3029 
3030 /*erSELECT_DOMINANT_INTERPOLATION
3031  Definition: Sets the interplation space defining the movement
3032  Opcode 124, Chapter 3.4.4, Page 3-66
3033  Return 0-OK, 1-Error
3034 */
3050 DLLAPI long ER_STDCALL erSELECT_DOMINANT_INTERPOLATION(ER_HND er_hnd, long dominant_int_type, long dominant_int_param=0);
3051 
3052 /*erSET_JOINT_SPEEDS
3053  Definition:
3054  sets the joint speed expressed as percentage of the maximal joint speed for each specified joint
3055  Opcode 131, Chapter 3.4.5, Page 3-74
3056 */
3070 DLLAPI long ER_STDCALL erSET_JOINT_SPEEDS(ER_HND er_hnd, long all_joint_flags, long joint_flags, double speed_percent);
3071 
3072 /*erSET_CARTESIAN_POSITION_SPEED
3073  Definition: speed for cartesian motion [m/sec]
3074  Opcode 133, Chapter 3.4.5, Page 3-75
3075  Return 0-OK, 1-Error
3076 */
3084 DLLAPI long ER_STDCALL erSET_CARTESIAN_POSITION_SPEED(ER_HND er_hnd, double speed_value);
3085 
3086 /*erSET_CARTESIAN_ORIENTATION_SPEED
3087  Definition: sets speed for the orientation during cartesian motion [rad/sec]
3088  Opcode 134, Chapter 3.4.5, Page 3-76
3089  Return 0-OK, 1-Error
3090 */
3100 DLLAPI long ER_STDCALL erSET_CARTESIAN_ORIENTATION_SPEED(ER_HND er_hnd, long rotation_no, double speed_ori_value);
3101 
3102 /*erSET_JOINT_ACCELERATIONS
3103  sets the joint accelerations expressed as percentage of the maximal joint acceleration for each specified joint
3104  Opcode 135, Chapter 3.4.5, Page 3-77
3105  Return 0-OK, 1-Error
3106 */
3123 DLLAPI long ER_STDCALL erSET_JOINT_ACCELERATIONS(ER_HND er_hnd, long all_joint_flags, long joint_flags, double accel_percent, long accel_type);
3124 
3125 /*erSET_CARTESIAN_POSITION_ACCELERATIONS
3126  Definition: sets acceleration for cartesian motion [m/sec^2]
3127  Opcode 137, Chapter 3.4.5, Page 3-78
3128  accel_type
3129  1: // accel
3130  2: // decel
3131  3: // accel + decel
3132 */
3143 DLLAPI long ER_STDCALL erSET_CARTESIAN_POSITION_ACCELERATION(ER_HND er_hnd, double accel_value, long accel_type);
3144 
3145 /*erSET_CARTESIAN_ORIENTATION_ACCELERATION
3146  Definition: sets the acceleration for the orientation during cartesian motion [rad/sec^2]
3147  Opcode 138, Chapter 3.4.5, Page 3-79
3148  Return 0-OK, 1-Error
3149 */
3162 DLLAPI long ER_STDCALL erSET_CARTESIAN_ORIENTATION_ACCELERATION(ER_HND er_hnd, long rotation_no, double accel_ori_value, long accel_type);
3163 
3164 /*erGET_CARTESIAN_POSITION_ACCELERATIONS
3165  Definition: gets acceleration for cartesian motion [m/sec^2]
3166  accel_type
3167  1: // accel
3168  2: // decel
3169  Return 0-OK, 1-Error
3170 */
3180 DLLAPI long ER_STDCALL erGET_CARTESIAN_POSITION_ACCELERATION(ER_HND er_hnd, double *accel_value, long accel_type);
3181 
3182 /*erGET_CARTESIAN_ORIENTATION_ACCELERATION
3183  Definition: Gets the acceleration for the orientation during cartesian motion [rad/sec^2]
3184  accel_type
3185  1: // accel
3186  2: // decel
3187  Return 0-OK, 1-Error
3188 */
3200 DLLAPI long ER_STDCALL erGET_CARTESIAN_ORIENTATION_ACCELERATION(ER_HND er_hnd, long rotation_no, double *accel_ori_value, long accel_type);
3201 
3202 /*erSET_JOINT_JERKS
3203  Definition: Sets the joint jerk expressed as a percentage of the maximal joint jerk for each specified joint.
3204  Opcode 162, Chapter 3.4.5, Page 3-80
3205  Return 0-OK, 1-Error, -1-not supported
3206 */
3223 DLLAPI long ER_STDCALL erSET_JOINT_JERKS(ER_HND er_hnd, long all_joint_flags, long joint_flags, double jerk_percent, long jerk_type);
3224 
3225 /*erSET_MOTION_TIME
3226  Definition: Specifies the motion time for the next motion
3227  Opcode 156, Chapter 3.4.5, Page 3-81
3228  Return 0-OK, 1-Error, -1-not supported
3229 */
3238 DLLAPI long ER_STDCALL erSET_MOTION_TIME(ER_HND er_hnd, double time_value);
3239 
3240 
3241 /*erSELECT_FLYBY_MODE
3242 */
3253 DLLAPI long ER_STDCALL erSELECT_FLYBY_MODE(ER_HND er_hnd, long flyby_on);
3254 
3255 /*erSET_FLYBY_CRITERIA_PARAMETER
3256  Definition: Sets the value of a flyby parameter
3257  Opcode 141, Chapter 3.4.6, Page 3-86
3258  Return 0-OK, 1-Error, -1- not supported
3259 */
3271 DLLAPI long ER_STDCALL erSET_FLYBY_CRITERIA_PARAMETER(ER_HND er_hnd, long param_number, long joint_nr, double param_value);
3272 
3273 /*erSELECT_FLYBY_CRITERIA
3274  Definition: Selects a flyby criterion (parameter)
3275  Opcode 142, Chapter 3.4.6, Page 3-87
3276  Return 0-OK, 1-Error, -1- not supported
3277 */
3287 DLLAPI long ER_STDCALL erSELECT_FLYBY_CRITERIA(ER_HND er_hnd, long param_number);
3288 
3289 /*erCANCEL_FLYBY_CRITERIA
3290  Definition: Cancels (unselects) a fly-by criterion
3291  Opcode 143, Chapter 3.4.6, Page 3-88
3292  Return 0-OK, 1-Error, -1- not supported
3293 */
3303 DLLAPI long ER_STDCALL erCANCEL_FLYBY_CRITERIA(ER_HND er_hnd, long param_number);
3304 
3305 /*erSELECT_POINT_ACCURACY
3306  Definition: Selects a criterion for when a target is reached
3307  Opcode 144, Chapter 3.4.6, Page 3-89
3308  Return 0-OK, 1-Error, -1- not supported
3309 */
3319 DLLAPI long ER_STDCALL erSELECT_POINT_ACCURACY(ER_HND er_hnd, long accuracy_type);
3320 
3321 /*erSET_POINT_ACCURACY_PARAMETER
3322  Definition: Sets the value of a parameter determining point accuracy
3323  Opcode 145, Chapter 3.4.6, Page 3-90
3324  Return 0-OK, 1-Error, -1- not supported
3325 */
3336 DLLAPI long ER_STDCALL erSET_POINT_ACCURACY_PARAMETER(ER_HND er_hnd, long accuracy_type, double accuracy_value );
3337 
3338 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3339 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3340 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3341 // MotionPlanner
3342 // class ERK_CAPI_MOP_PREP
3343 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3344 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3345 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3346 
3347 /* erSET_NEXT_TARGET
3348  sends the next target position. This may include intermediate position, radius, angle for circular motion
3349  Opcode 117, Chapter 3.4.3, Page 3-52
3350  Return
3351  1 - need more data, nothing to do
3352  0 - OK, next step is calculated successful
3353  -17 - specified motion type is not supported
3354  -34 - Error in matrix. Incomplete matrix
3355  -35 - Cartesian position expected
3356  -36 - Joint position expected
3357  -43 - Initial position not set
3358  -51 - no solution is found. One joint is out of range
3359  -52 - Cartesian position is out of work range
3360  -59 - specified position is singular
3361  -68 - fatal error, stopped calculating
3362  -71 - Position not stored, target buffer is full
3363  -78 - The specified position is not acceptable
3364  -79 - Not ready to receive targets
3365 */
3392 DLLAPI long ER_STDCALL erSET_NEXT_TARGET(ER_HND er_hnd, NEXT_TARGET_DATA *p_next_target_data);
3393 
3394 /* erSET_NEXT_TARGET_ADVANCE
3395  Definition: Sends about next target data
3396  Return 0-OK, 1-Error
3397 */
3408 DLLAPI long ER_STDCALL erSET_NEXT_TARGET_ADVANCE(ER_HND er_hnd, NEXT_TARGET_DATA_ADVANCE *p_next_target_data_advance);
3409 
3410 /*erSTOP_MOTION
3411  Definition: Stops the on-going motion toward the target
3412  Opcode 151, Chapter 3.4.8, Page 3-101
3413  Return 0-OK, 1-Error
3414 */
3426 DLLAPI long ER_STDCALL erSTOP_MOTION(ER_HND er_hnd);
3427 
3428 /*erCONTINUE_MOTION
3429  Definition: Continues a motion that was stopped with the erSTOP_MOTION() function
3430  Opcode 152, Chapter 3.4.8, Page 3-102
3431  Return 0-OK, 1-Error
3432 */
3444 
3445 /*erCANCEL_MOTION
3446  Definition: Cancel a motion that was stopped with erSTOP_MOTION() function
3447  Opcode 153, Chapter 3.4.8, Page 3-103
3448  Return 0-OK, 1-Error
3449 */
3461 
3462 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3463 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3464 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3465 // MotionPlanner
3466 // class ERK_CAPI_MOP_EXEC
3467 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3468 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3469 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3470 
3471 /* erGET_NEXT_STEP
3472  returns the next interpolated position step, the
3473  elapsed time and supplementary information like events, joint limits and messages
3474  Opcode 118, Chapter 3.4.3, Page 3-54
3475  Return
3476  2 - final step, target reached or speed is zero
3477  1 - need more data, nothing to do
3478  0 - OK, next step is calculated successful
3479  -13 - the specified output format is not supported
3480  -17 - the specified motion type is not supported
3481  -25 - the motion is not possible in the specified time
3482  -42 - no target set
3483  -51 - no solution is found. One joint is out of range
3484  -52 - Cartesian position is out of work range
3485  -68 - fatal error, stopped calculating
3486  -76 - incomplete or inconsistent motion specification, can't move
3487  -1053 - Cartesian position is out of boudary work range
3488  -1059 - Cartesian position is singular
3489 */
3521 DLLAPI long ER_STDCALL erGET_NEXT_STEP(ER_HND er_hnd, long output_format, NEXT_STEP_DATA *p_next_step_data, double time);
3522 
3532 DLLAPI long ER_STDCALL erGetCurrentStepData(ER_HND er_hnd, CURRENT_STEP_DATA *p_current_step_data);
3533 
3534 /*erSET_OVERRIDE_POSITION
3535  Definition: Sets a correction offset which will be added to the path during program execution
3536  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.
3537  Opcode 129, Chapter 3.4.4, Page 3-69
3538  Return 0-OK, 1-Error, -1- not supported
3539 */
3549 DLLAPI long ER_STDCALL erSET_OVERRIDE_POSITION(ER_HND er_hnd, DFRAME *PosOffset);
3550 
3551 /*erGET_CURRENT_TARGETID
3552  Definition: Returns the TargetID of the motion in execution
3553  Opcode 163, Chapter 3.4.6, Page 3-91
3554  Return 0-OK, 1-Error
3555 */
3564 
3565 #pragma endregion region_erk_devices
3566 
3567 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3568 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3569 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3570 // ToolPath
3571 // class ERK_CAPI_TOOLPATH
3572 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3573 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3574 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3575 
3576 #pragma region region_CTOOLPATH
3577 #pragma region region_toolpath
3578 
3604 DLLAPI long ER_STDCALL erInitToolPath (ER_HND er_hnd, ER_TOOLPATH_HND *er_tpth_hnd);
3605 
3612 
3623 DLLAPI long ER_STDCALL erInsertToolPath (ER_HND er_hnd, ER_TOOLPATH_HND *er_tpth_hnd, ER_TOOLPATH_HND er_tpth_hnd_ref);
3624 
3632 DLLAPI long ER_STDCALL erSwapToolPath (ER_TOOLPATH_HND er_tpth_hnd1, ER_TOOLPATH_HND er_tpth_hnd2);
3633 
3639 DLLAPI long ER_STDCALL erToolPathGetTargetLocationNumber (ER_TOOLPATH_HND er_tpth_hnd); // Number of Targets in ToolPath
3640 
3647 DLLAPI ER_HND ER_STDCALL erToolPathGetER_HND (ER_TOOLPATH_HND er_tpth_hnd); // Device Handle belonging to tool path handle
3648 
3653 DLLAPI char* ER_STDCALL erToolPathName (ER_TOOLPATH_HND er_tpth_hnd); // Name ToolPath
3654 
3661 DLLAPI long ER_STDCALL erToolPathEnable (ER_TOOLPATH_HND er_tpth_hnd, long enable); // 0-Disable, 1-Enable, 2-Status
3662 
3668 DLLAPI ER_HND ER_STDCALL erToolPathGetRobotHandle (ER_TOOLPATH_HND er_tpth_hnd); // Get Robot Handle belonging to tool path handle
3669 
3675 DLLAPI ER_HND ER_STDCALL erToolPathGetTrackMotionHandle (ER_TOOLPATH_HND er_tpth_hnd); // Get TrackMotion Handle belonging to tool path handle
3676 
3682 DLLAPI ER_HND ER_STDCALL erToolPathGetPositionerHandle (ER_TOOLPATH_HND er_tpth_hnd); // Get Positioner Handle belonging to tool path handle
3683 
3689 DLLAPI ER_HND ER_STDCALL erToolPathGetConveyorHandle (ER_TOOLPATH_HND er_tpth_hnd); // Get Conveyor Handle belonging to tool path handle
3690 
3699 DLLAPI long ER_STDCALL erToolPathSetTrackMotionHandle (ER_TOOLPATH_HND er_tpth_hnd, ER_HND hnd_TrackMotion=NULL); // Set TrackMotion Handle belonging to tool path handle
3708 DLLAPI long ER_STDCALL erToolPathSetPositionerHandle (ER_TOOLPATH_HND er_tpth_hnd, ER_HND hnd_Positioner=NULL); // Set Positioner Handle belonging to tool path handle
3717 DLLAPI long ER_STDCALL erToolPathSetConveyorHandle (ER_TOOLPATH_HND er_tpth_hnd, ER_HND hnd_Conveyor=NULL); // Set Conveyor Handle belonging to tool path handle
3718 
3723 DLLAPI char* ER_STDCALL erToolPathLogFileName (ER_TOOLPATH_HND er_tpth_hnd); // Log File Name ToolPath
3728 DLLAPI char* ER_STDCALL erToolPathPrgFileName (ER_TOOLPATH_HND er_tpth_hnd); // Prg File Name ToolPath
3729 
3735 
3741 
3749 DLLAPI long ER_STDCALL CpyEventsTemplate(ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_EVENTS_HND hnd); // Copy target events data to template
3756 DLLAPI ER_TARGET_EVENTS_HND ER_STDCALL GetEventsTemplateHnd(ER_TOOLPATH_HND er_tpth_hnd); // Get handle to internal events template data
3757 
3765 DLLAPI long ER_STDCALL CpyMotionAttributesTemplate (ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_ATTRIBUTES_HND hnd); // Copy target attributes data to template
3766 
3773 DLLAPI ER_TARGET_ATTRIBUTES_HND ER_STDCALL GetMotionAttributesTemplateHnd (ER_TOOLPATH_HND er_tpth_hnd); // Get handle to internal attributes template data
3774 
3783 
3791 
3800 
3808 
3817 
3825 
3834 
3842 
3851 
3859 
3860 
3867 DLLAPI long ER_STDCALL erToolPathReset (ER_TOOLPATH_HND er_tpth_hnd); // Reset all tool path target locations
3868 
3877 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
3878 
3887 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
3888 
3897 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
3898 
3907 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
3908 
3917 DLLAPI long ER_STDCALL erToolPathSetInitPos(ER_TOOLPATH_HND er_tpth_hnd, double InterpolationTime=0); // Initializes the MotionPlanner based on current settings
3918 
3919 //DLLAPI long ER_STDCALL erToolPathRunAdv (ER_TOOLPATH_HND er_tpth_hnd);
3920 
3974 
4077 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);
4078 
4085 
4094 
4095 //DLLAPI long ER_STDCALL erToolPathDefinition (ER_TOOLPATH_HND er_tpth_hnd); // erzeugt einige TargetLocations
4096 
4097 #pragma endregion region_toolpath
4098 
4099 //--------------------------------
4100 // Target Location ... ERK_CAPI_TOOLPATH_TARGETS
4101 //--------------------------------
4102 
4103 #pragma region region_TargetLocations
4104 
4105 // Target Locations
4114 DLLAPI long ER_STDCALL erTargetLocationReset (ER_TARGET_LOCATION_HND er_tarloc_hnd); // Reset target location
4115 
4138 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);
4157 
4162 DLLAPI long ER_STDCALL erGetTargetLocationNumber (ER_TARGET_LOCATION_HND er_tarloc_hnd); // Number of Targets in ToolPath
4167 DLLAPI ER_HND ER_STDCALL erhGetTargetLocationER_HND (ER_TARGET_LOCATION_HND er_tarloc_hnd); // Device Handle belonging to target location handle
4168 
4193 
4206 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);
4222 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);
4238 DLLAPI long ER_STDCALL erSetTargetLocation_Move_Joint_Frame(ER_TARGET_LOCATION_HND er_tarloc_hnd, DFRAME *CartPosFrame, long configuration = 0, long ptp_target_calculation_mode = ER_PTP_TARGET_CALC_MODE_UNDEF, double speed_percent = 0, double override_speed = 0, DFRAME *ToolFrame = 0, DFRAME *BaseFrame = 0);
4251 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);
4267 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);
4283 DLLAPI long ER_STDCALL erSetTargetLocation_Move_Slew_Frame(ER_TARGET_LOCATION_HND er_tarloc_hnd, DFRAME *CartPosFrame, long configuration = 0, long ptp_target_calculation_mode = ER_PTP_TARGET_CALC_MODE_UNDEF, double speed_percent = 0, double override_speed = 0, DFRAME *ToolFrame = 0, DFRAME *BaseFrame = 0);
4299 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);
4315 DLLAPI long ER_STDCALL erSetTargetLocation_Move_LIN_Frame(ER_TARGET_LOCATION_HND er_tarloc_hnd, DFRAME *CartPosFrame, double speed_cp = 0, double speed_ori = 0, double override_speed = 0, long flyby_on = -1, DFRAME *ToolFrame = 0, DFRAME *BaseFrame = 0);
4332 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);
4349 DLLAPI long ER_STDCALL erSetTargetLocation_Move_CIRC_Frame(ER_TARGET_LOCATION_HND er_tarloc_hnd, DFRAME *CartPosFrameVia, DFRAME *CartPosFrame, double speed_cp = 0, double speed_ori = 0, double override_speed = 0, long flyby_on = -1, DFRAME *ToolFrame = 0, DFRAME *BaseFrame = 0);
4350 //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);
4351 //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);
4352 
4353 #pragma endregion region_TargetLocations
4354 
4355 //--------------------------------
4356 // Header Data ... TARGET_HEAD, ERK_CAPI_TOOLPATH_HEAD
4357 //--------------------------------
4358 #pragma region region_HeaderData
4359 
4360  // Header Data
4401 DLLAPI long ER_STDCALL erTargetLocationValid (ER_TARGET_LOCATION_HND er_tarloc_hnd, long valid); // 0-Disable, 1-Enable, 2-Status
4402 #pragma endregion region_HeaderData
4403 
4404 //------------------------------------------------------------------------------
4405 // Instructions, individual information text ... TARGET_INSTRUCTIONS
4406 //------------------------------------------------------------------------------
4407 #pragma region region_Instructions
4408 
4424 DLLAPI char *ER_STDCALL erGetInstructions_information (ER_TARGET_LOCATION_HND er_tarloc_hnd); // User defined individual information text
4431 DLLAPI char *ER_STDCALL erGetInstructions_LeadInstructions (ER_TARGET_LOCATION_HND er_tarloc_hnd); // Instructions separated by semicolon, when target is reached
4438 DLLAPI char *ER_STDCALL erGetInstructions_LagInstructions (ER_TARGET_LOCATION_HND er_tarloc_hnd); // Instructions separated by semicolon, before move will start
4448 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
4449 #pragma endregion region_Instructions
4450 
4451 //--------------------------------
4452 // Events ... TARGET_EVENTS
4453 //--------------------------------
4454 #pragma region region_Events
4455 
4456  // Events
4496 DLLAPI long ER_STDCALL erSetEvents_EventDOUT(ER_TARGET_EVENTS_HND hnd, int idx = 1, long io_value = ER_EVENT_BOOL_UNDEF, char *io_name = 0, long strig_type = ER_EVENT_TRIGGER_OFF, double strig_time = 0, double strig_dist = 0, long ttrig_type = ER_EVENT_TRIGGER_OFF, double ttrig_time = 0, double ttrig_dist = 0);
4513 DLLAPI long ER_STDCALL erGetEvents_EventDOUT(ER_TARGET_EVENTS_HND hnd, int idx, long *io_value, char *io_name, long *strig_type, double *strig_time, double *strig_dist, long *ttrig_type, double *ttrig_time, double *ttrig_dist);
4514 
4545 DLLAPI long ER_STDCALL erSetEvents_EventDIN (ER_TARGET_EVENTS_HND hnd, int idx = 1, long io_value = ER_EVENT_BOOL_UNDEF, char *io_name = 0, long leadcond_type = ER_EVENT_CONDITION_UNDEF, double leadcond_value = 0, long lagcond_type = ER_EVENT_CONDITION_UNDEF, double lagcond_value = 0);
4546 
4547 #pragma endregion region_Events
4548 
4549 //--------------------------------
4550 // Auxiliary Motion Attributes ... TARGET_ATTRIBUTES_AUX
4551 //--------------------------------
4552 #pragma region region_AuxMotionAttributes
4553 
4554  // Auxiliary Motion Attributes
4561 
4562 #pragma endregion region_AuxMotionAttributes
4563 
4564 //--------------------------------
4565 // Motion Attributes ... TARGET_ATTRIBUTES
4566 //--------------------------------
4567 #pragma region region_MotionAttributes
4568  // Motion Attributes
4585 DLLAPI long *ER_STDCALL erGetMotionAttributes_enabled (ER_TARGET_ATTRIBUTES_HND hnd); // enables/disables this target
4591 DLLAPI TErTargetID *ER_STDCALL erGetMotionAttributes_target_id (ER_TARGET_ATTRIBUTES_HND hnd); // unique target ID, NEXT_TARGET_DATA.TargetID
4599 DLLAPI double *ER_STDCALL erGetMotionAttributes_WobjCartPosVec(ER_TARGET_ATTRIBUTES_HND hnd); // WorkObject valid for all cartesian targets CartPosVec, CartPosVecVia
4608 DLLAPI DFRAME *ER_STDCALL erGetMotionAttributes_WobjCartPosFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *WobjCartPosFrame); // WorkObject valid for all cartesian targets CartPosVec, CartPosVecVia
4617 DLLAPI DFRAME *ER_STDCALL erSetMotionAttributes_WobjCartPosFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *WobjCartPosFrame); // WorkObject valid for all cartesian targets CartPosVec, CartPosVecVia
4618 
4625 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()
4634 DLLAPI double *ER_STDCALL erGetMotionAttributes_BaseVec(ER_TARGET_ATTRIBUTES_HND hnd); // work object, $BASE, $UFrame has only effect if ::IPO_MODE_BASE, erSetBaseRobotBase()
4635 
4645 DLLAPI DFRAME *ER_STDCALL erGetMotionAttributes_BaseFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *BaseFrame); // work object, $BASE, $UFrame has only effect if ::IPO_MODE_BASE, erSetBaseRobotBase()
4655 DLLAPI DFRAME *ER_STDCALL erSetMotionAttributes_BaseFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *BaseFrame); // work object, $BASE, $UFrame has only effect if ::IPO_MODE_BASE, erSetBaseRobotBase()
4656 
4664 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()
4672 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()
4673 
4674 
4701 
4702 
4719 
4720 
4729 
4739 
4749 
4766 
4793 
4810 
4811 
4819 DLLAPI double *ER_STDCALL erGetMotionAttributes_ToolVec (ER_TARGET_ATTRIBUTES_HND hnd); // Tool/TCP data, erSetTool()
4820 
4830 
4840 
4841 
4849 DLLAPI long *ER_STDCALL erGetMotionAttributes_ToolIdx (ER_TARGET_ATTRIBUTES_HND hnd); // user defined Idx for Tool/TCP data, erSetTool()
4857 DLLAPI char *ER_STDCALL erGetMotionAttributes_ToolName (ER_TARGET_ATTRIBUTES_HND hnd); // user defined Name for Tool/TCP data, erSetTool()
4858 
4866 DLLAPI double *ER_STDCALL erGetMotionAttributes_ToolOffsetVec(ER_TARGET_ATTRIBUTES_HND hnd); // Tool/TCP offset data, erSetToolOffset()
4885 
4886 
4894 DLLAPI long *ER_STDCALL erGetMotionAttributes_ToolOffsetIdx(ER_TARGET_ATTRIBUTES_HND hnd); // user defined Idx for Tool/TCP offset data, erSetToolOffset()
4902 DLLAPI char *ER_STDCALL erGetMotionAttributes_ToolOffsetName(ER_TARGET_ATTRIBUTES_HND hnd); // user defined Name for Tool/TCP offset data, erSetToolOffset()
4903 
4917 
4935 DLLAPI long *ER_STDCALL erGetMotionAttributes_motype (ER_TARGET_ATTRIBUTES_HND hnd); // ER_JOINT , ER_LIN, ER_SLEW, ER_CIRC, erSELECT_MOTION_TYPE()
4945 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()
4953 DLLAPI long *ER_STDCALL erGetMotionAttributes_advance_motion (ER_TARGET_ATTRIBUTES_HND hnd); // look ahead by 1 is only supported, erSET_ADVANCE_MOTION()
4961 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()
4970 DLLAPI double *ER_STDCALL erGetMotionAttributes_acc (ER_TARGET_ATTRIBUTES_HND hnd); // 20-100[%] Set lagging of accelerations deceleration, erSetAccSet()
4979 DLLAPI double *ER_STDCALL erGetMotionAttributes_ramp (ER_TARGET_ATTRIBUTES_HND hnd); // 20-100[%] Set lagging of accelerations deceleration, erSetAccSet()
4989 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()
4999 DLLAPI long *ER_STDCALL erGetMotionAttributes_flyby_on (ER_TARGET_ATTRIBUTES_HND hnd); // 0-OFF, 1-ON only when LIN or CIRC, erSELECT_FLYBY_MODE()
5009 DLLAPI double *ER_STDCALL erGetMotionAttributes_flyby_speed_percent (ER_TARGET_ATTRIBUTES_HND hnd); // if flyby_on enabled: [%], erSET_FLYBY_CRITERIA_PARAMETER(), tbd
5019 DLLAPI double *ER_STDCALL erGetMotionAttributes_flyby_dist (ER_TARGET_ATTRIBUTES_HND hnd); // if flyby_on enabled: [m], erSET_FLYBY_CRITERIA_PARAMETER(), tbd
5035 DLLAPI long *ER_STDCALL erGetMotionAttributes_autoaccel (ER_TARGET_ATTRIBUTES_HND hnd); // ER_AUTOACCEL_MODE_OFF, -_POS, -_ORI, -_AX, -_DEF, -_ON, erSetAutoAccel()
5044 DLLAPI double *ER_STDCALL erGetMotionAttributes_LeadWaitTime (ER_TARGET_ATTRIBUTES_HND hnd); // Wait time [s], before move will start, NEXT_TARGET_DATA.LeadWaitTime
5053 DLLAPI double *ER_STDCALL erGetMotionAttributes_LagWaitTime (ER_TARGET_ATTRIBUTES_HND hnd); // Wait time [s], after robot reaches its target, NEXT_TARGET_DATA.LagWaitTime
5054 
5055 #pragma endregion region_MotionAttributes
5056 
5057 //--------------------------------
5058 // Target data for Joint Move ... ERK_CAPI_TOOLPATH_MOVE_JOINT
5059 //--------------------------------
5060 #pragma region region_MoveJoint
5061 
5080 DLLAPI long *ER_STDCALL erGetMoveJoint_target_type (ER_TARGET_MOVE_JOINT_HND hnd); // ER_TARGET_TYPE_ABS, ER_TARGET_TYPE_ABSJOINT, erSELECT_TARGET_TYPE()
5086 DLLAPI double *ER_STDCALL erGetMoveJoint_speed_percent (ER_TARGET_MOVE_JOINT_HND hnd); // joint speed [%], erSET_JOINT_SPEEDS()
5092 DLLAPI double *ER_STDCALL erGetMoveJoint_accel_percent (ER_TARGET_MOVE_JOINT_HND hnd); // joint acceleration [%], erSET_JOINT_ACCELERATIONS()
5102 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
5113 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
5119 DLLAPI long *ER_STDCALL erGetMoveJoint_configuration (ER_TARGET_MOVE_JOINT_HND hnd); // Target manipulator configuration string, NEXT_TARGET_DATA.Configuration
5127 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
5135 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[]
5136 
5137 #pragma endregion region_MoveJoint
5138 
5139 //--------------------------------
5140 // Target data for CP Move ... ERK_CAPI_TOOLPATH_MOVE_CP
5141 //--------------------------------
5142 #pragma region region_MoveCP
5143 
5161 DLLAPI long *ER_STDCALL erGetMoveCP_target_type (ER_TARGET_MOVE_CP_HND hnd); // ER_TARGET_TYPE_ABS
5167 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()
5173 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()
5179 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()
5185 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()
5196 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
5206 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
5214 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()
5228 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()
5229 #pragma endregion region_MoveCP
5230 
5231 //--------------------------------
5232 // Motion execution data at target ... ERK_CAPI_TOOLPATH_MOTION_EXEC
5233 //--------------------------------
5234 #pragma region region_MotionExec
5235 
5257 DLLAPI long ER_STDCALL erGetMotionExec_motion_success (ER_TARGET_MOTION_EXEC_HND hnd); // 1 - TARGET_LOCATION reached successfully, 0 - TARGET_LOCATION not reached successfully
5264 DLLAPI double ER_STDCALL erGetMotionExec_time_stamp (ER_TARGET_MOTION_EXEC_HND hnd); // Time stamp [s] when target location is reached
5269 DLLAPI double ER_STDCALL erGetMotionExec_trajectory_time (ER_TARGET_MOTION_EXEC_HND hnd); // Trajectory Time [s] for current motion to target
5283 DLLAPI long ER_STDCALL erGetMotionExec_configuration (ER_TARGET_MOTION_EXEC_HND hnd); // current manipulator configuration at target location, [1..number of robot configurations]
5289 DLLAPI double *ER_STDCALL erGetMotionExec_JointPos (ER_TARGET_MOTION_EXEC_HND hnd); // Joint Location at target location
5295 DLLAPI double *ER_STDCALL erGetMotionExec_ExtAxValues (ER_TARGET_MOTION_EXEC_HND hnd); // External axis values at target location
5296 #pragma endregion region_MotionExec
5297 
5298 //--------------------------------
5299 // External axis data definition for Track/Slider-Motion ... ERK_CAPI_TOOLPATH_EXTAX_TRACKMOTION
5300 //--------------------------------
5301 #pragma region region_ExtAxTrack
5302  // External axis data definition for Track/Slider-Motion
5357 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
5365 DLLAPI long *ER_STDCALL erGetExtAxTrack_sync_type (ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND hnd); // ER_SYNC_OFF, ER_SYNC_ON, erConnectTrackMotionSetSync()
5379 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[]
5393 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);
5394 #pragma endregion region_ExtAxTrack
5395 
5396 //--------------------------------
5397 // External axis data definition for Positioner/TurnTable ... ERK_CAPI_TOOLPATH_EXTAX_POSITIONER
5398 //--------------------------------
5399 #pragma region region_ExtAxPositioner
5400 
5466 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
5474 DLLAPI long *ER_STDCALL erGetExtAxPositioner_sync_type (ER_TARGET_EXTAX_DEVICE_POSITIONER_HND hnd); // ER_SYNC_OFF, ER_SYNC_ON, erConnectPositionerSetSync()
5488 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[]
5502 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);
5503 #pragma endregion region_ExtAxPositioner
5504 
5505 //--------------------------------
5506 // External axis data definition for Conveyor ... ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND
5507 //--------------------------------
5508 #pragma region region_ExtAxConveyor
5509 
5527  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
5535  DLLAPI long *ER_STDCALL erGetExtAxConveyor_sync_type(ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND hnd); // ER_SYNC_OFF, ER_SYNC_ON, erConnectConveyorSetSync()
5549  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[]
5563  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);
5564 
5584  DLLAPI long ER_STDCALL erSetConveyorTrackingWindow(ER_TARGET_LOCATION_HND er_tarloc_hnd, long active, double up, double down, TErTrackingWindowID id_tw, char *name = NULL);
5585 
5596 #pragma endregion region_ExtAxConveyor
5597 
5598 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5599 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5600 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5601 // ToolBox
5602 // class ERK_CAPI_TOOLPATH_TOOLBOX
5603 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5604 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5605 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5606 #pragma region region_Toolpath_Toolbox
5607 
5617 DLLAPI long ER_STDCALL erTPth_TBox_Fct(int FctIdx, int FctSubIdx, ER_TOOLPATH_HND er_tpth_hnd, int constraint_param, char *svalues=NULL);
5618 #pragma endregion region_Toolpath_Toolbox
5619 
5620 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5621 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5622 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5623 // ToolBox
5624 // class ERK_CAPI_TOOLPATH_APIPP
5625 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5626 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5627 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5628 #pragma region region_apipp_dll
5629 
5668 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);
5669 #pragma endregion region_apipp_dll
5670 
5671 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5672 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5673 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5674 // ToolPath
5675 // class ERK_CAPI_TOOLPATH_CREATE
5676 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5677 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5678 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5684 DLLAPI long ER_STDCALL erTPth_Fct(ER_TOOLPATH_HND er_tpth_hnd);
5685 #pragma endregion region_CTOOLPATH
5686 
5687 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5688 // class ERK_CAPI_SIM
5689 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5690 
5691 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5692 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5693 // erColl_ - Functions
5694 // class ERK_CAPI_SIM_COLLISION
5695 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5696 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
5697 
5698 #pragma region region_erSimCollision
5699 
5700 /* Creates a collision handle for one Model and preallocate memory for n_tris triangles
5701 */
5710 DLLAPI long ER_STDCALL erColl_BeginModel(ER_COLLISION_HND *er_coll_hnd, long n_tris);
5711 
5712 /* Adds a triangle to a Model
5713 */
5725 DLLAPI long ER_STDCALL erColl_AddTri(ER_COLLISION_HND er_coll_hnd, double *p1, double *p2, double *p3, long id);
5726 
5727 /* Stop building a Model
5728 */
5736 
5737 /* Perform the collision check of two Models
5738 See also erColl_ChkCollision_res() to get the collision results immediately
5739 */
5893 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);
5894 
5895 /* Perform the collision check of two Models
5896  Collision results returned immediately compared to erColl_ChkCollision()
5897  */
6241 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);
6242 
6274 DLLAPI long ER_STDCALL erColl_ChkCollision_res_free(long query_type, void *pres);
6275 
6276 /* Unload a Model. Free all allocated memory
6277 */
6285 
6286 /* Get Collision result for query ::ER_COLL_QUERY_TYPE_COLLIDE
6287 */
6297 /* Get Collision result for query ::ER_COLL_QUERY_TYPE_DISTANCE
6298 */
6308 
6309 /* Get Collision result for query ::ER_COLL_QUERY_TYPE_TOLERANCE
6310 */
6320 
6321 #pragma endregion region_erSimCollision
6322 
6323 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6324 // ERK_CAPI_AUTOPATH
6325 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6326 #pragma region region_autopath_sdk
6327 
6330 DLLAPI char* ER_STDCALL erk_AutoPathVer(void);
6331 
6339 
6415 
6423 
6431 
6498 DLLAPI int ER_STDCALL erk_AutoPath_SetCallback_CheckConstraints(BOOL(*ptr_CheckConstraints)(int, void*));
6499 
6507 DLLAPI int ER_STDCALL erk_AutoPathSetPoseStart(double *pose_start);
6508 
6516 DLLAPI int ER_STDCALL erk_AutoPathSetPoseEnd(double *pose_end);
6517 
6525 
6530 
6535 
6540 
6545 
6550 
6557 
6565 
6571 
6576 
6581 DLLAPI double* ER_STDCALL erk_AutoPathGetWayPoint(int idx);
6587 
6593 DLLAPI int ER_STDCALL erk_AutoPathSetAccuracy(UINT accuracy);
6594 
6604 DLLAPI int ER_STDCALL erk_AutoPathSetAxisConstraints(int axisBit = AUTOPATH_SDK_AXIS_BIT_DOF6, int setting = 0, double qConstraintMin = 0, double qConstraintMax = 0);
6605 
6612 DLLAPI int ER_STDCALL erk_AutoPathSetAxisPriority(int axisBit, int priority);
6617 DLLAPI int ER_STDCALL erk_AutoPathSetAxisEnable(int axisBit, int enable);
6618 
6635 DLLAPI int ER_STDCALL erk_AutoPathSetParameter(int ap_option, int ap_value);
6651 DLLAPI int ER_STDCALL erk_AutoPathGetParameter(int ap_option);
6652 
6686 DLLAPI int ER_STDCALL erk_AutoPathGetResults(int ap_result);
6687 
6688 #pragma endregion region_autopath_sdk
6689 
6690 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6691 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6692 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6693 // class ERK_CAPI_GEO
6694 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6695 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6696 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6697 #pragma region region_geo
6698 /* erUpdateGeo
6699  Update all Models for each robot joint
6700 */
6709 DLLAPI long ER_STDCALL erUpdateGeo(ER_HND er_hnd);
6710 #pragma endregion region_geo
6711 
6712 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6713 // class ERK_CAPI_GEO_MNGR
6714 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6715 #pragma region region_GeoMngr
6716 //~~~~~~~~~~~~~~~~~~~~~
6717 // Administration
6718 //~~~~~~~~~~~~~~~~~~~~~
6723 
6730 
6738 
6739 //~~~~~~~~~~~~~~~~~~~~~
6740 // Access to geometries
6741 //~~~~~~~~~~~~~~~~~~~~~
6748 // fills structure pointed to by p_load_geometry_data with geometry loading data
6749 DLLAPI int ER_STDCALL erGeoMngr_GetGeometry(ER_HND er_hnd, int geometryIndex, LOAD_GEOMETRY_DATA *p_load_geometry_data, DFRAME* kinMat);
6750 // return number of geometries for axis of a specified device
6751 DLLAPI int ER_STDCALL erGeoMngr_GetNumAxisGeometries(ER_HND er_hnd, int axis_nr);
6752 // fills structure pointed to by p_load_geometry_data with geometry loading data
6753 DLLAPI int ER_STDCALL erGeoMngr_GetAxisGeometry(ER_HND er_hnd, int axis_nr, int geometryIndex, LOAD_GEOMETRY_DATA *p_load_geometry_data, DFRAME* kinMat);
6754 // BBox über die gesamte Geometrie (also über den gesamten Body)
6755 DLLAPI const double* ER_STDCALL erGeoMngr_GetGeometryBBox(TErGeoHandle geometryHandle);
6756 // Achsen-BBox über alle Geometry-BBoxes einer Achse
6757 DLLAPI const double* ER_STDCALL erGeoMngr_GetAxisBBox(ER_HND er_hnd, int axis_id);
6758 // Device-BBox
6759 DLLAPI const double* ER_STDCALL erGeoMngr_GetDeviceBBox(ER_HND er_hnd);
6760 
6762 
6763 DLLAPI int ER_STDCALL erGeoMngr_GetGeometryObjNumPoints(TErGeoHandle geometryHandle, int objidx);
6764 DLLAPI double* ER_STDCALL erGeoMngr_GetGeometryObjPoint(TErGeoHandle geometryHandle, int objidx, int index);
6766 DLLAPI double* ER_STDCALL erGeoMngr_GetGeometryObjPointNormal(TErGeoHandle geometryHandle, int objidx, int index);
6767 DLLAPI int ER_STDCALL erGeoMngr_GetGeometryObjNumLines(TErGeoHandle geometryHandle, int objidx);
6768 DLLAPI size_t* ER_STDCALL erGeoMngr_GetGeometryObjLine(TErGeoHandle geometryHandle, int objidx, int index);
6769 DLLAPI int ER_STDCALL erGeoMngr_GetGeometryObjNumPolygons(TErGeoHandle geometryHandle, int objidx);
6770 DLLAPI size_t* ER_STDCALL erGeoMngr_GetGeometryObjPolygon(TErGeoHandle geometryHandle, int objidx, int index);
6771 
6772 // ist die Obj-Color intern -2 (USER_COLOR) wird die user color (die Farbe, die in der LOAD_GEOMETRY_DATA-Struktur steht) zurückgegeben
6773 // sonst : konkrete Farbe
6774 DLLAPI double* ER_STDCALL erGeoMngr_GetGeometryObjColor(TErGeoHandle geometryHandle, int objidx);
6775 // der Farbcode (kann auch -2 (USER_COLOR) sein, damit die Host-Applikation eine eigene UserColor festlegen kann)
6776 DLLAPI long ER_STDCALL erGeoMngr_GetGeometryObjColorCode(TErGeoHandle geometryHandle, int objidx);
6777 
6778 DLLAPI int ER_STDCALL erGeoMngr_GetGeometryCloneCount(TErGeoHandle geometryHandle); // Get number of clones >=1
6780 
6781 //DLLAPI double* ER_STDCALL erGeoMngr_GetGeometryPolygoneNormal(TErGeoHandle geometryHandle, int index);
6782 //DLLAPI double* ER_STDCALL erGeoMngr_GetGeometryPolygoneCenter(TErGeoHandle geometryHandle, int index);
6783 
6786 DLLAPI int ER_STDCALL erGeoMngr_SetGeometryIsCollided(TErGeoHandle geometryHandle, int isCollided);
6788 
6789 DLLAPI int ER_STDCALL erGeoMngr_CheckBoundingBoxCollision(DFRAME* T1, const double* bbox1, DFRAME* T2, const double* bbox2, double tolerance);
6790 #pragma endregion region_GeoMngr
6791 
6792 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6793 // class ERK_CAPI_SYS
6794 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6795 
6796 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6797 // class ERK_CAPI_SYS_UTILITIES
6798 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6799 
6800 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6801 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6802 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6803 // erMath_ - Functions
6804 // ERK_CAPI_SYS_MATHEMATICS
6805 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6806 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6807 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
6808 
6809 #pragma region region_erMath
6810 
6825 DLLAPI long ER_STDCALL erMath_FrameToVecIdx(DFRAME *T, double *vec, long rotation_idx=ER_ROT_XYZ);
6826 
6841 DLLAPI long ER_STDCALL erMath_VecToFrameIdx(double *vec, DFRAME *T, long rotation_idx=ER_ROT_XYZ);
6842 
6857 DLLAPI long ER_STDCALL erMath_PxyzRxyzToFrame(double x,double y,double z,double Rx,double Ry,double Rz, DFRAME *T);
6858 
6866 DLLAPI long ER_STDCALL erMath_Frame_Ident(DFRAME *T); // T = Ident
6867 
6878 DLLAPI long ER_STDCALL erMath_Frame_Trans(DFRAME *T, double x, double y, double z); // set frame position T.p[] = [x,y,z]
6879 
6891 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)
6892 
6903 DLLAPI long ER_STDCALL erMath_AngleBetween(DFRAME *Ts, DFRAME *Te, double *angle, double *k=NULL);
6904 
6915 DLLAPI long ER_STDCALL erMath_DistBetween(DFRAME *Ts, DFRAME *Te, double *dist, double *dv=NULL);
6916 
6929 DLLAPI long ER_STDCALL erMath_CircCenterPoint(double *ps, double *pv, double *pe, DFRAME *pTc, double *radius, double *phi, double *phi_via = NULL);
6930 
6939 DLLAPI long ER_STDCALL erMath_invT(DFRAME *To,DFRAME *Ti); // To = inv(Ti)
6940 
6949 DLLAPI long ER_STDCALL erMath_invR(DFRAME *Ro,DFRAME *Ri); // Ro = inv(Ri) = transpose(Ri) = Ri'
6950 
6960 DLLAPI long ER_STDCALL erMath_mul_R_R(DFRAME *Ro,DFRAME *Ri1,DFRAME *Ri2); // Ro = Ri1 * Ri2
6961 
6971 DLLAPI long ER_STDCALL erMath_mul_T_T(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2); // To = Ti1 * Ti2
6972 
6984 DLLAPI long ER_STDCALL erMath_mul_T_invT (DFRAME *To, DFRAME *Ti1, DFRAME *Ti2); // To = Ti1 * inv(Ti2)
6985 
6997 DLLAPI long ER_STDCALL erMath_mul_invT_T (DFRAME *To, DFRAME *Ti1, DFRAME *Ti2); // To = inv(Ti1) * Ti2
6998 
7010 DLLAPI long ER_STDCALL erMath_mul_invT_invT (DFRAME *To, DFRAME *Ti1, DFRAME *Ti2); // To = inv(Ti1) * inv(Ti2)
7011 
7022 DLLAPI long ER_STDCALL erMath_mul_T_pos (double *po,DFRAME *T,double *pi); // po = T * pi
7023 
7035 DLLAPI long ER_STDCALL erMath_mul_invT_pos (double *po,DFRAME *T,double *pi); // po = inv(T) * pi
7036 
7046 DLLAPI long ER_STDCALL erMath_mul_R_pos (double *po,DFRAME *R,double *pi); // po = R * pi
7047 
7059 DLLAPI long ER_STDCALL erMath_mul_invR_pos (double *po,DFRAME *R,double *pi); // po = R' * pi
7060 
7071 DLLAPI long ER_STDCALL erMath_mul_T_T_T(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = Ti1 * Ti2 * Ti3
7072 
7085 DLLAPI long ER_STDCALL erMath_mul_T_T_invT(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = Ti1 * Ti2 * inv(Ti3)
7086 
7099 DLLAPI long ER_STDCALL erMath_mul_T_invT_T(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = Ti1 * inv(Ti2) * Ti3
7100 
7113 DLLAPI long ER_STDCALL erMath_mul_T_invT_invT(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = Ti1 * inv(Ti2) * inv(Ti3)
7114 
7127 DLLAPI long ER_STDCALL erMath_mul_invT_T_T(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = inv(Ti1) * Ti2 * Ti3
7128 
7141 DLLAPI long ER_STDCALL erMath_mul_invT_T_invT(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = inv(Ti1) * Ti2 * inv(Ti3)
7142 
7155 DLLAPI long ER_STDCALL erMath_mul_invT_invT_T(DFRAME *To,DFRAME *Ti1,DFRAME *Ti2,DFRAME *Ti3); // To = inv(Ti1) * inv(Ti2) * Ti3
7156 
7169 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)
7170 
7181 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
7194 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]
7207 DLLAPI DFRAME* ER_STDCALL erMath_SetFramePosOri(DFRAME *To, 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] to a DFRAME
7219 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
7226 DLLAPI double* ER_STDCALL erMath_CpyVec(double *dst, double *src, int n); // cpy vector of size n
7232 DLLAPI double* ER_STDCALL erMath_ResetVec(double *dst, int n); // reset vector of size n
7233 
7234 #pragma endregion region_erMath
7235 
7236 //------------------------------------------------------------------------------------------
7237 //------------------------------------------------------------------------------------------
7238 
7239 #ifdef __cplusplus
7240 }
7241 #endif
7242 
7243 #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:192
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:744
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()....
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 DFRAME *ER_STDCALL erSetMotionAttributes_ToolOffsetFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *ToolOffsetFrame)
ToolOffset (TCP) for a target location Offset Transformation from TCP see inq_ToolOffsetIdx(),...
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 long ER_STDCALL erSetTargetLocation_Move_CIRC_Frame(ER_TARGET_LOCATION_HND er_tarloc_hnd, DFRAME *CartPosFrameVia, DFRAME *CartPosFrame, double speed_cp=0, double speed_ori=0, double override_speed=0, long flyby_on=-1, DFRAME *ToolFrame=0, DFRAME *BaseFrame=0)
Move_CIRC, continious path motion definition for target location Remarks Use erAddTargetLocation() t...
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,...
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,...
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:84
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 int ER_STDCALL erk_AutoPathGetWayPointDof(void)
Get dof of calculated way points.
const long ER_EVENT_CONDITION_UNDEF
event condition for binary input is undefined
Definition: erk_capi_types.h:601
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....
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:207
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 int ER_STDCALL erk_AutoPathSetAxisEnable(int axisBit, int enable)
Set axis enable.
DLLAPI double *ER_STDCALL erGetMoveJoint_JointPos(ER_TARGET_MOVE_JOINT_HND hnd)
Joint position for joint move for target location Remarks Use for.
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:678
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....
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 ...
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 double *ER_STDCALL erk_AutoPathGetConfigurationPose(void)
current configuration pose during FindPath Process return pointer, size nConfig
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 ...
const int AUTOPATH_SDK_AXIS_BIT_DOF6
axisBit Axis 1..6
Definition: erk_capi_types.h:844
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:75
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 DFRAME *ER_STDCALL erSetMotionAttributes_extTcpOffsetFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *extTcpOffsetFrame)
external Tool/TCP offset data w.r.t. extTcpBase, extTcpWorld, for a target location Transformation fr...
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 DFRAME *ER_STDCALL erGetMotionAttributes_BaseFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *BaseFrame)
Program shift Base for a target location Base '$BASE, $UFrame' has only if IPO_MODE_BASE is set and e...
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...
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 'target location handle' 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 double *ER_STDCALL erk_AutoPathGetEndPose(void)
Get End Pose return pointer, size nConfig.
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 int ER_STDCALL erk_AutoPathGetPlanningStatus(void)
Get path planning status The planning status is one of AUTOPATH_SDK_STATUS_MP_IDLE AUTOPATH_SDK_STA...
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 erk_AutoPathSetMem(AutoPath_ConfigurationSpace *apcs)
allocate memory for AutoPath_ConfigurationSpace data depending on nConfig see example AutoPathInit()
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:721
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...
DLLAPI long ER_STDCALL erSetEvents_DIN(ER_HND er_hnd, int idx=1, long io_value=ER_EVENT_BOOL_UNDEF, char *io_name=0, long leadcond_type=ER_EVENT_CONDITION_UNDEF, double leadcond_value=0, long lagcond_type=ER_EVENT_CONDITION_UNDEF, double lagcond_value=0)
Set event conditions for a binary input for target location An input is checked before a movement sta...
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:801
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....
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 [>0-1000%] for joint move for target location.
DLLAPI DFRAME *ER_STDCALL erSetMotionAttributes_extTcpWorldFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *extTcpWorldFrame)
external Tool (TCP) w.r.t. Robot World or flange of positioner, for a target location Transformation ...
unsigned int * ER_TARGET_EXTAX_DEVICE_POSITIONER_HND
unique External axis data definition for Positioner/TurnTable handle
Definition: erk_capi_types.h:210
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 int ER_STDCALL erk_AutoPathTerminate(AutoPath_ConfigurationSpace *apcs)
Terminate AutoPath call AutoPathFreeMem() first, see example AutoPathInit()
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)
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:639
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 through the complete tool path Rem...
DLLAPI long ER_STDCALL erGetBackLink(ER_HND er_hnd, long *backlink)
Get robot back link status, obsolete function, use erGetBacklink()
DLLAPI int ER_STDCALL erk_AutoPathSetAxisPriority(int axisBit, int priority)
Set axis priority.
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 char *ER_STDCALL erk_AutoPathVer(void)
AutoPath Version.
DLLAPI int ER_STDCALL erk_AutoPathGetParameter(int ap_option)
Get parameter Paramter ap_option is one of AUTOPATH_SDK_PARAMETER_DYNADJUST AUTOPATH_SDK_PARAMETER_...
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:200
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,...
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....
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...
void(ER_STDCALL * TerLogProc)(long LogType, char *LogMessage)
Callback function type definition for Log messages, erSetCallBack_LogProc()
Definition: erk_capi_types.h:623
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....
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:564
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,...
DLLAPI ER_HND ER_STDCALL erConnectPositionerGetHND(ER_HND er_hnd)
Get robots connection handle between robot and positioner. See also erConnectPositioner()
DLLAPI double *ER_STDCALL erk_AutoPathGetAxisConstraintsMin(void)
Get minimum axis constraints return pointer, size nConfig.
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 int ER_STDCALL erk_AutoPathFindPath(void)
Start motion planner, find a collision free path between start and end pose In each step,...
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....
DLLAPI DFRAME *ER_STDCALL erGetMotionAttributes_extTcpWorldFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *extTcpWorldFrame)
external Tool (TCP) w.r.t. Robot World or flange of positioner, for a target location Transformation ...
Collision results for query ER_COLL_QUERY_TYPE_COLLIDE, see erColl_GetResults_Collide() .
Definition: erk_capi_types.h:772
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 erSetTargetLocation_Move_LIN_Frame(ER_TARGET_LOCATION_HND er_tarloc_hnd, DFRAME *CartPosFrame, double speed_cp=0, double speed_ori=0, double override_speed=0, long flyby_on=-1, DFRAME *ToolFrame=0, DFRAME *BaseFrame=0)
Move_LIN, continious path motion definition for target location Remarks Use erAddTargetLocation() to...
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:209
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,...
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 erk_AutoPathGetStartPose(void)
Get Start Pose return pointer, size nConfig.
DLLAPI double *ER_STDCALL erGetMotionAttributes_BaseVec(ER_TARGET_ATTRIBUTES_HND hnd)
Program shift Base for a target location Base '$BASE, $UFrame' 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....
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 DFRAME *ER_STDCALL erGetMotionAttributes_ToolFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *ToolFrame)
Tool (TCP) for a target location Transformation from Tip to TCP see inq_ToolIdx(),...
DLLAPI int ER_STDCALL erGeoMngr_GetGeometryObjNumPoints(TErGeoHandle geometryHandle, int objidx)
DLLAPI long ER_STDCALL erSetTargetLocation_Move_Joint_Frame(ER_TARGET_LOCATION_HND er_tarloc_hnd, DFRAME *CartPosFrame, long configuration=0, long ptp_target_calculation_mode=ER_PTP_TARGET_CALC_MODE_UNDEF, double speed_percent=0, double override_speed=0, DFRAME *ToolFrame=0, DFRAME *BaseFrame=0)
Move_Joint, full synchronized PTP, motion definition for target location Remarks Use erAddTargetLoca...
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 through the complet...
DLLAPI DFRAME *ER_STDCALL erSetMotionAttributes_WobjCartPosFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *WobjCartPosFrame)
Set WorkObject valid for all cartesian target locations such as CartPosVec, CartPosVecVia Using this ...
DLLAPI double *ER_STDCALL erk_AutoPathGetWayPoint(int idx)
Get way point.
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...
unsigned int * ER_TARGET_EVENTS_HND
unique Events handle
Definition: erk_capi_types.h:203
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 erSetEvents_DOUT(ER_HND er_hnd, int idx=1, long io_value=ER_EVENT_BOOL_UNDEF, char *io_name=0, long strig_type=ER_EVENT_TRIGGER_OFF, double strig_time=0, double strig_dist=0, long ttrig_type=ER_EVENT_TRIGGER_OFF, double ttrig_time=0, double ttrig_dist=0)
Set an event for a boolean output A boolean event for binary outputs is controlled by trigger data,...
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....
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...
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:669
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....
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,...
DLLAPI int ER_STDCALL erk_AutoPathInit(AutoPath_ConfigurationSpace *apcs)
Initialize AutoPath Call this functions to setup the autopath configuration space Parameter apcs defi...
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:205
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 erSetTargetLocation_Move_Slew_Frame(ER_TARGET_LOCATION_HND er_tarloc_hnd, DFRAME *CartPosFrame, long configuration=0, long ptp_target_calculation_mode=ER_PTP_TARGET_CALC_MODE_UNDEF, double speed_percent=0, double override_speed=0, DFRAME *ToolFrame=0, DFRAME *BaseFrame=0)
Move_Slew, not synchronized PTP, motion definition for target location Remarks Use erAddTargetLocati...
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....
DLLAPI DFRAME *ER_STDCALL erGetMotionAttributes_WobjCartPosFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *WobjCartPosFrame)
Get WorkObject valid for all cartesian target locations such as CartPosVec, CartPosVecVia Using this ...
const long ER_PTP_TARGET_CALC_MODE_UNDEF
default ER_PTP_TARGET_CALC_MODE_SHORTEST_ANGLE, NEXT_TARGET_DATA
Definition: erk_capi_types.h:396
#define DLLAPI
Definition: erk_capi_types.h:74
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....
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 through the...
DLLAPI int ER_STDCALL erk_AutoPathSetParameter(int ap_option, int ap_value)
Set parameter Paramter ap_option is one of AUTOPATH_SDK_PARAMETER_DYNADJUST AUTOPATH_SDK_PARAMETER_A...
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 erGetToolFix(ER_HND er_hnd, DFRAME *tTwfix)
Get robot tool fix (TCP) data w.r.t. robots flange, without Tool Offset.
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:630
DLLAPI long ER_STDCALL erKernelAddLicenseFile(char *license_file)
Set an additional location and name of license file. Call this function before initializing the Kerne...
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,...
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 through the complete tool path.
External axis target data for connected devices belongs to structure NEXT_TARGET_DATA.
DLLAPI long ER_STDCALL erSetEvents_EventDIN(ER_TARGET_EVENTS_HND hnd, int idx=1, long io_value=ER_EVENT_BOOL_UNDEF, char *io_name=0, long leadcond_type=ER_EVENT_CONDITION_UNDEF, double leadcond_value=0, long lagcond_type=ER_EVENT_CONDITION_UNDEF, double lagcond_value=0)
Set event conditions for a binary input for target location An input is checked before a movement sta...
DLLAPI long ER_STDCALL erGetAutoAccel(ER_HND er_hnd, long *autoaccel)
Get status for automatic calculation of acceleration depending on programmed speed....
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 DFRAME *ER_STDCALL erGetMotionAttributes_extTcpBaseFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *extTcpBaseFrame)
external Tool (TCP) w.r.t. Robot Base or flange of positioner, for a target location Transformation f...
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...
const long ER_EVENT_TRIGGER_OFF
Signal Trigger to control binary output. OFF will not set output event.
Definition: erk_capi_types.h:597
DLLAPI double *ER_STDCALL erGetMoveJoint_accel_percent(ER_TARGET_MOVE_JOINT_HND hnd)
Accel_percent percentage acceleration definition [>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...
const long ER_EVENT_BOOL_UNDEF
Event status for binary input/output events is undefined.
Definition: erk_capi_types.h:593
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:194
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 erSetEvents_EventDOUT(ER_TARGET_EVENTS_HND hnd, int idx=1, long io_value=ER_EVENT_BOOL_UNDEF, char *io_name=0, long strig_type=ER_EVENT_TRIGGER_OFF, double strig_time=0, double strig_dist=0, long ttrig_type=ER_EVENT_TRIGGER_OFF, double ttrig_time=0, double ttrig_dist=0)
Set an event for a boolean output for target location A boolean event for binary outputs is controlle...
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....
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....
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,...
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 'target location handle' 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 int ER_STDCALL erk_AutoPath_SetCallback_CheckConstraints(BOOL(*ptr_CheckConstraints)(int, void *))
Defines a callback function to check constraints during AutoPath calculation The callback function is...
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 ER_TARGET_EVENTS_HND ER_STDCALL GetEventsTemplateHnd(ER_TOOLPATH_HND er_tpth_hnd)
Get events template data from tool path. Get the events template data belonging to the tool path er_t...
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:749
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() ...
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(),...
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,...
const long ER_SYNC_UNDEF
device synchronization not defined
Definition: erk_capi_types.h:352
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,...
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:195
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:369
DLLAPI long ER_STDCALL erConnectRobotGetSync(ER_HND er_hnd)
Get robots synchronization flag for synchronization between robot and slave robot....
unsigned int * ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND
unique External device definition for Conveyor
Definition: erk_capi_types.h:211
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 double *ER_STDCALL erk_AutoPathGetAxisConstraintsMax(void)
Get maximum axis constraints return pointer, size nConfig.
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 'pjnt' to the moveable base 'mb'. 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...
DLLAPI int ER_STDCALL erk_AutoPathFreeMem(AutoPath_ConfigurationSpace *apcs)
free memory of AutoPath_ConfigurationSpace data see example AutoPathInit()
unsigned int * ER_TOOLPATH_HND
unique Tool path handle, created with erInitToolPath()
Definition: erk_capi_types.h:199
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....
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 ER_HND ER_STDCALL erToolPathGetER_HND(ER_TOOLPATH_HND er_tpth_hnd)
Device Handle belonging to tool path. This method is obsolete -> use erToolPathGetRobotHandle()
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], time to reach the target location, while interpolation through the complete tool...
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 CpyEventsTemplate(ER_TOOLPATH_HND er_tpth_hnd, ER_TARGET_EVENTS_HND hnd)
Copy events to template data. The events defined with events handle hnd are copied to the events temp...
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 'b' to the moveable base 'mb'. 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 DFRAME *ER_STDCALL erSetMotionAttributes_BaseFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *BaseFrame)
Program shift Base for a target location Base '$BASE, $UFrame' has only if IPO_MODE_BASE is set and e...
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 erSetToolOffset(ER_HND er_hnd, DFRAME *wTwo)
Set robot tool offset (TCP) data w.r.t. robots fix Tcp.
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....
DLLAPI DFRAME *ER_STDCALL erGetMotionAttributes_ToolOffsetFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *ToolOffsetFrame)
ToolOffset (TCP) for a target location Offset Transformation from TCP see inq_ToolOffsetIdx(),...
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:193
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,...
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...
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:726
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:787
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 "advance move" 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:202
Geometry data structure for callback function. Used when loading and updating robot geometries With c...
Definition: erk_capi_types.h:254
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:197
long(ER_STDCALL * TerFreeGeometryProc)(ER_HND ErHandle, TErGeoHandle GeoHandle)
Callback function type definition to free or delete a geometry, erSetCallBack_FreeGeometryProc()....
Definition: erk_capi_types.h:648
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' ,...
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 long ER_STDCALL erGetEvents_EventDOUT(ER_TARGET_EVENTS_HND hnd, int idx, long *io_value, char *io_name, long *strig_type, double *strig_time, double *strig_dist, long *ttrig_type, double *ttrig_time, double *ttrig_dist)
Get an event for a boolean output for target location A boolean event for binary outputs is controlle...
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,...
unsigned int * ER_TARGET_MOVE_JOINT_HND
unique Target data for Joint Move handle
Definition: erk_capi_types.h:206
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 int ER_STDCALL erk_AutoPathAbortPlanning(void)
Abort path planning use GetPlanningStatus()
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 int ER_STDCALL erk_AutoPathSetPoseEnd(double *pose_end)
Set end configuration Remarks This pose must be valid - collision free, based on callback function "...
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(),...
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 int ER_STDCALL erk_AutoPathGetNumberOfWayPoints(void)
Get number of calculated way points, including start and end pose call this method after FindPath() s...
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 erMath_CircCenterPoint(double *ps, double *pv, double *pe, DFRAME *pTc, double *radius, double *phi, double *phi_via=NULL)
Circle calculation from three points ps over pv to pe. Calculates center of circle,...
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:196
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 int ER_STDCALL erk_AutoPathSetAccuracy(UINT accuracy)
Set accuracy.
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 DFRAME *ER_STDCALL erSetMotionAttributes_extTcpBaseFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *extTcpBaseFrame)
external Tool (TCP) w.r.t. Robot Base or flange of positioner, for a target location Transformation f...
DLLAPI long ER_STDCALL erGetToolOffset(ER_HND er_hnd, DFRAME *wTwo)
Get robot tool offset (TCP) data w.r.t. robots fix Tcp.
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 DFRAME *ER_STDCALL erMath_SetFramePosOri(DFRAME *To, double x, double y, double z, double Rx, double Ry, double Rz)
Cpy and convert a target location (position+orientation) to a DFRAME position x,y,...
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 through 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,...
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 DFRAME *ER_STDCALL erSetMotionAttributes_ToolFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *ToolFrame)
Tool (TCP) for a target location Transformation from Tip to TCP see inq_ToolIdx(),...
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 DFRAME *ER_STDCALL erGetMotionAttributes_extTcpOffsetFrame(ER_TARGET_ATTRIBUTES_HND hnd, DFRAME *extTcpOffsetFrame)
external Tool/TCP offset data w.r.t. extTcpBase, extTcpWorld, for a target location Transformation fr...
DLLAPI int ER_STDCALL erk_AutoPathClearAllWayPoints(void)
Clear all way points.
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.
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:201
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....
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....
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()...
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)
Definition: erk_capi_types.h:915
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 erGetMotionAttributes_speed_reduction_enable(ER_TARGET_ATTRIBUTES_HND hnd)
Speed reduction enable for a target location The speed reduction enable can be one of the following v...
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 int ER_STDCALL erk_AutoPathGetResults(int ap_result)
Get results Paramter ap_result is one of AUTOPATH_SDK_RESULT_CHECKS AUTOPATH_SDK_RESULT_SECONDS AU...
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....
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:208
DLLAPI ER_TARGET_EVENTS_HND ER_STDCALL erGetTargetLocationEventsHnd(ER_TARGET_LOCATION_HND er_tarloc_hnd)
Handle for target events data.
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 'target location handle' 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....
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.
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:659
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,...
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 int ER_STDCALL erk_AutoPathSetAxisConstraints(int axisBit=AUTOPATH_SDK_AXIS_BIT_DOF6, int setting=0, double qConstraintMin=0, double qConstraintMax=0)
Set axis constraints Parameter setting is a bitwise inclusive OR operator (|) of AUTOPATH_SDK_CONSTRA...
DLLAPI int ER_STDCALL erk_AutoPathSetPoseStart(double *pose_start)
Set start configuration Remarks This pose must be valid - collision free, based on callback function...
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.
unsigned int * ER_TARGET_ATTRIBUTES_AUX_HND
unique Auxiliary motion attributes handle
Definition: erk_capi_types.h:204
DLLAPI char *ER_STDCALL erToolPathName(ER_TOOLPATH_HND er_tpth_hnd)
Name of 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,...