EASY-ROBâ„¢ Kernel  v8.606
erk_capi_types.h
Go to the documentation of this file.
1 /*
2  EASY-ROB Robotics Simulation Kernel
3 
4  EASY-ROB Software GmbH
5 
6  Copyright (c) 1996 - 2023
7 
8  Date: APR 2023
9  Version: 8.606
10 
11  Header file
12  erk_capi_types.h
13 
14  Autor
15  EASY-ROB Software GmbH
16 
17  Versions
18  v6303 nov 2013
19  v6306 may 2014
20  v6307 aug 2014
21  v6310 dec 2014
22  v6601 jan 2015
23  v6603 feb 2015
24  v6604 mar 2015
25  v6606 jul 2015
26  v6608 jul 2015 VS 2012
27  v6609 jul 2015 erColl_ChkCollision_res() thread save
28  v6610 sep 2015 erColl_ChkCollision_res_free()
29  v6611 dec 2015 Support ER_MOTION_FILTER_GEO for external axis
30  v6612 jan 2916 BugFix MultiKIN Option, erGet_n_Kin_IR()
31  v7001 mar 2016 Major Release, MatrixLock
32  v7002 jun 2016
33  v7003 jul 2016 0-DOF Devices
34  v7004 aug 2016
35  v7005 sep 2016
36  v7302 apr 2017
37  v7305 sep 2017
38  v7306 dec 2017
39  v7309 mar 2018
40  v7601 apr 2018
41  v7602 may 2018 API PostProc
42  v7603 jul 2018
43  v7606 nov 2018
44  v7607 feb 2019 autopath
45  v8001 aug 2019
46  v8003 sep 2019
47  v8004 dec 2019
48  v8005 feb 2020
49  v8006 may 2020
50  v8007 jun 2020
51  v8301 jul 2020
52  v8307 jul 2021
53  v8308 nov 2021
54  v8602 mar 2022 Pre Release
55  v8603 aug 2022 Pre Release
56  v8604 sep 2022 Pre Release
57  v8605 oct 2022 Pre Release
58  v8606 apr 2023 BugFix loc_FreeGrp(()
59 */
60 
61 #ifndef _erk_capi_types_h
62 #define _erk_capi_types_h
63 
64 #ifdef _WIN32
65 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
66 // Windows
67 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
68 //
69 #define DLLAPI __declspec(dllexport)
70 #define ER_STDCALL __stdcall
71 
72 #else
73 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
74 // Linux
75 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
76 //
77 #define DLLAPI
78 #define ER_STDCALL
79 
80 #endif //_WIN32
81 
87 typedef struct {
88  double n[3],
89  o[3],
90  a[3],
91  p[3];
92 } DFRAME;
93 
94 const long ER_KIN_CONFIGS = 8;
95 const long ER_KIN_DOFS = 12;
96 const long ER_KIN_PASSIVE_JNTS = 36;
97 const long ER_DOF6 = 6;
98 const long ER_DOF_QUAT = 7;
99 const long ER_DOF9 = 9;
100 const long ER_DOF12 = 12;
101 const long ER_DIM = 3;
102 const long ER_MAXSTR = 128;
103 const long ER_DMAXSTR = 256;
104 const long ER_LS_MAXSTR = 512;
105 const long ER_HS_MAXSTR = 1024;
106 
107 const double ER_PI = 3.14159265359;
108 const double ER_DEG = 180.0/ER_PI;
109 const double ER_RAD = ER_PI/180.0;
110 const double ER_mm2m = 0.001;
111 const double ER_m2mm = 1000.0;
112 
113 const int ER_APIDLL_CNTRL_UNDEF = 0x0;
115 const int ER_APIDLL_CNTRL_TERMINATE = 0x2;
116 const int ER_APIDLL_CNTRL_SIM_START = 0x4;
117 const int ER_APIDLL_CNTRL_SIM_STEP = 0x8;
118 const int ER_APIDLL_CNTRL_SIM_STOP = 0x10;
119 
120 //const int ER_APIDLL_CALL_UNDEF = 0x0; // undefined
121 //const int ER_APIDLL_CALL_LOAD_CELL = 0x1; // load_cell APIDLL_CNTRL_INITIALIZE
122 //const int ER_APIDLL_CALL_LOAD_ROBOT = 0x2; // load_robot APIDLL_CNTRL_INITIALIZE
123 //const int ER_APIDLL_CALL_LOAD_ROBOT_DATA_K = 0x4; // load_new_robot_data APIDLL_CNTRL_INITIALIZE KIN
124 //const int ER_APIDLL_CALL_LOAD_ROBOT_DATA_I = 0x8; // load_new_robot_data APIDLL_CNTRL_INITIALIZE IPO
125 //const int ER_APIDLL_CALL_LOAD_ROBOT_DATA_D = 0x10;// load_new_robot_data APIDLL_CNTRL_INITIALIZE DYN
126 //const int ER_APIDLL_CALL_DELETE_ROBOT = 0x20; // data_delete_robot, APIDLL_CNTRL_TERMINATE
127 //const int ER_APIDLL_CALL_DELETE_ROBOT_ALL = 0x40; // RemoveRobot_All, APIDLL_CNTRL_TERMINATE
128 //const int ER_APIDLL_CALL_CREATE_ROBOT = 0x80; // createkinematic_ext APIDLL_CNTRL_INITIALIZE
129 //const int ER_APIDLL_CALL_MODIFY_INVKIN = 0x100; // modify_invkin APIDLL_CNTRL_INITIALIZE
130 //const int ER_APIDLL_CALL_IPO_ALL_MODE = 0x200; // ipo all motypes APIDLL_CNTRL_INITIALIZE, APIDLL_CNTRL_SIM_START, APIDLL_CNTRL_SIM_STOP
131 //const int ER_APIDLL_CALL_IPO_JOINT = 0x400; // ipo_joint APIDLL_CNTRL_INITIALIZE, APIDLL_CNTRL_SIM_START, APIDLL_CNTRL_SIM_STOP
132 //const int ER_APIDLL_CALL_IPO_CP = 0x800; // ipo_cp APIDLL_CNTRL_INITIALIZE, APIDLL_CNTRL_SIM_START, APIDLL_CNTRL_SIM_STOP
133 //const int ER_APIDLL_CALL_IPO_CIRC = 0x1000; // ipo_circ APIDLL_CNTRL_INITIALIZE, APIDLL_CNTRL_SIM_START, APIDLL_CNTRL_SIM_STOP
134 //
135 //const int ER_APIDLL_DEVIDX_ALL = 0; // For all devices
136 //const int ER_APIDLL_DEVIDX_CURRENT = -1; // For the current device only
137 
138 #ifdef _WIN64
139 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
140 // Windows x64
141 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
142 //
143 typedef UINT_PTR* ER_HND;
144 typedef UINT_PTR* Host_HND;
145 typedef UINT_PTR TErGeoHandle;
146 typedef UINT_PTR TErTargetID;
147 typedef UINT_PTR TErTrackingWindowID;
148 typedef UINT_PTR *ER_COLLISION_HND;
149 
150 typedef UINT_PTR *ER_TOOLPATH_HND;
151 typedef UINT_PTR *ER_TARGET_LOCATION_HND;
152 typedef UINT_PTR *ER_TARGET_HEAD_HND;
153 typedef UINT_PTR *ER_TARGET_INSTRUCTIONS_HND;
154 typedef UINT_PTR *ER_TARGET_EVENTS_HND;
155 typedef UINT_PTR *ER_TARGET_ATTRIBUTES_AUX_HND;
156 typedef UINT_PTR *ER_TARGET_ATTRIBUTES_HND;
157 typedef UINT_PTR *ER_TARGET_MOVE_JOINT_HND;
158 typedef UINT_PTR *ER_TARGET_MOVE_CP_HND;
159 typedef UINT_PTR *ER_TARGET_MOTION_EXEC_HND;
160 typedef UINT_PTR *ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND;
161 typedef UINT_PTR *ER_TARGET_EXTAX_DEVICE_POSITIONER_HND;
162 typedef UINT_PTR *ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND;
163 
164 #elif _WIN32
165 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
166 // Windows
167 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
168 //
169 typedef unsigned int* ER_HND;
170 typedef unsigned int* Host_HND;
171 typedef unsigned int TErGeoHandle;
172 typedef unsigned int TErTargetID;
173 typedef unsigned int TErTrackingWindowID;
174 typedef unsigned int *ER_COLLISION_HND;
175 
176 typedef unsigned int *ER_TOOLPATH_HND;
177 typedef unsigned int *ER_TARGET_LOCATION_HND;
178 typedef unsigned int *ER_TARGET_HEAD_HND;
179 typedef unsigned int *ER_TARGET_INSTRUCTIONS_HND;
180 typedef unsigned int *ER_TARGET_EVENTS_HND;
181 typedef unsigned int *ER_TARGET_ATTRIBUTES_AUX_HND;
182 typedef unsigned int *ER_TARGET_ATTRIBUTES_HND;
183 typedef unsigned int *ER_TARGET_MOVE_JOINT_HND;
184 typedef unsigned int *ER_TARGET_MOVE_CP_HND;
185 typedef unsigned int *ER_TARGET_MOTION_EXEC_HND;
186 typedef unsigned int *ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND;
187 typedef unsigned int *ER_TARGET_EXTAX_DEVICE_POSITIONER_HND;
188 typedef unsigned int *ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND;
189 
190 #else
191 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
192 // Linux
193 //~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
194 //
195 typedef unsigned int* ER_HND;
196 typedef unsigned int* Host_HND;
197 typedef unsigned int TErGeoHandle;
198 typedef unsigned int TErTargetID;
199 typedef unsigned int TErTrackingWindowID;
200 typedef unsigned int *ER_COLLISION_HND;
201 
202 typedef unsigned int *ER_TOOLPATH_HND;
203 typedef unsigned int *ER_TARGET_LOCATION_HND;
204 typedef unsigned int *ER_TARGET_HEAD_HND;
205 typedef unsigned int *ER_TARGET_INSTRUCTIONS_HND;
206 typedef unsigned int *ER_TARGET_EVENTS_HND;
207 typedef unsigned int *ER_TARGET_ATTRIBUTES_AUX_HND;
208 typedef unsigned int *ER_TARGET_ATTRIBUTES_HND;
209 typedef unsigned int *ER_TARGET_MOVE_JOINT_HND;
210 typedef unsigned int *ER_TARGET_MOVE_CP_HND;
211 typedef unsigned int *ER_TARGET_MOTION_EXEC_HND;
214 typedef unsigned int *ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND;
215 
216 #endif //_WIN32
217 
218 
219 const long ER_GEO_TYPE_CUBE = 1;
220 const long ER_GEO_TYPE_PYRAMID = 2;
221 const long ER_GEO_TYPE_WEDGE = 3;
222 const long ER_GEO_TYPE_CYLINDER = 4;
223 const long ER_GEO_TYPE_CONE = 5;
224 const long ER_GEO_TYPE_SPHERE = 6;
225 const long ER_GEO_TYPE_IGP = 9;
226 const long ER_GEO_TYPE_STL = 11;
227 const long ER_GEO_TYPE_3DS = 12;
228 
229 const long ER_GEO_PARAMETER_MAX = 12;
230 
231 const int ER_GEO_ATTRIBUTES_UNDEF = 0x0;
232 const int ER_GEO_ATTRIBUTES_SMOOTH = 0x1;
233 const int ER_GEO_ATTRIBUTES_WIRE = 0x2;
234 const int ER_GEO_ATTRIBUTES_BBFLAT = 0x4;
235 const int ER_GEO_ATTRIBUTES_BBWIRE = 0x8;
236 const int ER_GEO_ATTRIBUTES_INVISIBLE = 0x10;
237 const int ER_GEO_ATTRIBUTES_VERTICES = 0x20;
238 const int ER_GEO_ATTRIBUTES_FLAT = 0x40;
239 const int ER_GEO_ATTRIBUTES_INVERT = 0x100;
241 const int ER_GEO_ATTRIBUTES_SHOW_NAME = 0x400;
243 const int ER_GEO_ATTRIBUTES_SHOW_MESH = 0x1000;
244 const int ER_GEO_ATTRIBUTES_SHOW_EDGES = 0x2000;
246 const int ER_GEO_ATTRIBUTES_CHK_COLLISION = 0x10000;
251 
257 typedef struct {
259  char *FileName;
260  char *GeoName;
261  long RGBColor;
262  double *Scaling;
264  long ax_idx;
265  long GeoType;
271 } LOAD_GEOMETRY_DATA; // HostLoadGeometry LoadGeometryProc
272 
273 const long ER_LICENSE_PRIORITY_UNDEF = 0x0;
274 const long ER_LICENSE_PRIORITY_LMNGR = 0x1;
275 const long ER_LICENSE_PRIORITY_LOCAL = 0x2;
277 
278 const long ER_LOG_TYPE_CONSOLE = -1;
279 const long ER_LOG_TYPE_MSG = 0;
280 const long ER_LOG_TYPE_WARNING = 1;
281 const long ER_LOG_TYPE_ERROR = 2;
282 const long ER_LOG_TYPE_STATUS = 3;
283 
284 const long ER_NOTIFY_TYPE_MSG = 0;
285 const long ER_NOTIFY_TYPE_WARNING = 1;
286 const long ER_NOTIFY_TYPE_ERROR = 2;
288 
289 const long ER_NOTIFY_DOMAIN_OK = 0;
290 const long ER_NOTIFY_DOMAIN_GLOBAL = 1;
291 const long ER_NOTIFY_DOMAIN_FILE_IO = 2;
295 
296 const long ER_NOTIFY_CODE_OK = 0;
297 
299 const long ER_NOTIFY_CODE_WARN_UNREACH = 202;
303 const long ER_NOTIFY_CODE_WARN_ERROR = 206;
305 
314 
324 
329 typedef struct {
334  char Msg[ER_MAXSTR];
335 } TErNotifyData; // HostNotify NotifyProc
336 typedef void* TErExtraData;
337 
339 const long ER_GRPSYNC_SET_DURATION = 1;
343 
348 typedef struct {
349  long SyncType;
351  double value;
352 } TErGrpSyncData; // HostGrpSync GrpSyncProc
353 
354 // erConnect* NEW_050402 CONNECT_SYNC_UNDEF, ....
355 const long ER_SYNC_UNDEF =0x0;
356 const long ER_SYNC_OFF =0x1;
357 const long ER_SYNC_ON =0x2;
358 const long ER_SYNC_CONVEYOR =0x4;
359 const long ER_SYNC_VR_OFF =0x8;
361 
362 const long ER_RRRRRR_ID =1;
363 const long ER_TTTRRR_ID =2;
364 const long ER_RRRRRR_BL_ID =3;
365 const long ER_UNIV_ROB_ID =10;
366 const long ER_DH_ID =11;
367 
372 typedef struct {
374  double JointPos[ER_KIN_DOFS];
375  char Configuration[ER_MAXSTR];
377 
378 const long ER_TARGET_TYPE_ABS = 0;
379 const long ER_TARGET_TYPE_ABSJOINT = 9;
380 
386 
387 const long ER_MOTION_FILTER_GEO = 0;
388 const long ER_MOTION_FILTER_C2 = 1;
389 
392 
393 const long ER_JOINT = 1;
394 const long ER_PTP = ER_JOINT;
395 const long ER_LIN = 2;
396 const long ER_SLEW = 3;
397 const long ER_CIRC = 4;
398 
405 
406 const long ER_AUTOACCEL_MODE_OFF =0x0;
407 const long ER_AUTOACCEL_MODE_POS =0x1;
408 const long ER_AUTOACCEL_MODE_ORI =0x2;
409 const long ER_AUTOACCEL_MODE_AX =0x4;
412 
417 
423 
428 typedef struct _ER_EXTAX_KIN_DATA {
430  long axis_idx;
431  double axis_value;
432  double speed_value;
434 
435 const long ER_EXTAX_KIN_DATA_MAX = 12;
436 
442 typedef struct _NEXT_TARGET_DATA {
444  long TargetParam;
449  double TrajectoryTime;
451  double LeadWaitTime;
452  double LagWaitTime;
458 
459 const long ER_FLYBY_OFF = 0;
460 const long ER_FLYBY_ON = 1;
461 
462 const long ER_FLYBY_TYPE_UNDEF = 0;
463 const long ER_FLYBY_TYPE_SPEED = 1;
464 const long ER_FLYBY_TYPE_DISTANCE = 2;
465 
474  long MotionType;
475  long target_type;
476  double speed_value;
479  double segment_length;
480  long flyby_type;
481  double flyby_value;
488 
489 const long TRK_WND_NOT_ACTIVE = 0;
490 const long TRK_WND_WAITING = 1;
491 const long TRK_WND_INSIDE = 2;
492 const long TRK_WND_OUT_OF_BOUNDARY = 3;
493 
498 typedef struct _NEXT_STEP_DATA {
502  double ElapsedTime;
503  long JointLimit;
506  double TrajectoryTime;
511 
512 const long ER_CSTEP_STATUS_UNDEF =0x0;
513 const long ER_CSTEP_STATUS_ERROR =0x1;
514 const long ER_CSTEP_STATUS_OK =0x2;
515 const long ER_CSTEP_STATUS_VIA_POINT =0x4;
519 const long ER_CSTEP_STATUS_INV_WARNING =0x40;
520 
525 typedef struct _CURRENT_STEP_DATA {
528  long step_number;
531  long n_dof;
541  long MotionType;
542  long ExternalTcp;
543 
544  double SpeedReduce;
545  double OverrideSpeed;
549 
551  double TrajectoryTime;
555 
556  double PathLength;
559 
560  double Distance;
561  double DistanceMoving;
564 
565 // ERK_CAPI_TOOLPATH
566 const int ER_MOP_GNTPS_CNTRL_UNDEF = 0x0;
567 const int ER_MOP_GNTPS_CNTRL_INIT = 0x1;
570 const int ER_MOP_GNTPS_CNTRL_TBD_08 = 0x8;
571 
573 
574 const int ER_MOP_GNTPS_CNTRL_LOG_FILE = 0x100;
575 const int ER_MOP_GNTPS_CNTRL_PRG_FILE = 0x200;
578 
579 const int ER_MOP_GNT_ERROR = -1;
580 const int ER_MOP_GNT_OK_SUCCESS = 0;
581 const int ER_MOP_GNT_NO_TARGETS = -2;
582 
583 const int ER_MOP_SNT_ERROR = -1;
584 const int ER_MOP_SNT_OK_SUCCESS = 0;
586 
587 const int ER_MOP_GNS_ERROR = -1;
588 const int ER_MOP_GNS_OK_SUCCESS = 0;
592 
593 // EVENTS
594 const int ER_EVENT_BOOL_N = 32;
595 
596 const long ER_EVENT_BOOL_UNDEF = 0x0;
597 const long ER_EVENT_BOOL_OFF = 0x1;
598 const long ER_EVENT_BOOL_ON = 0x2;
599 
600 const long ER_EVENT_TRIGGER_OFF = 0x0;
601 const long ER_EVENT_TRIGGER_DWN = 0x1;
602 const long ER_EVENT_TRIGGER_UP = 0x2;
603 
604 const long ER_EVENT_CONDITION_UNDEF = 0x0;
609 const long ER_EVENT_CONDITION_WAIT_DIN_LT = 0x100;
610 const long ER_EVENT_CONDITION_WAIT_DIN_LE = 0x200;
611 
612 // Deklaration of Callback functions
613 // TerLogProc
614 // TerLoadGeometryProc
615 // TerUpdateGeometryProc
616 // TerFreeGeometryProc
617 // TerGetActualTravelRangesProc
618 // TerNotifyProc
619 // TerGrpSyncProc
620 //
626 typedef void (ER_STDCALL* TerLogProc)(long LogType, char *LogMessage);
627 
633 typedef TErGeoHandle (ER_STDCALL* TerLoadGeometryProc)(ER_HND ErHandle, LOAD_GEOMETRY_DATA *p_load_geometry_data);
634 
642 typedef long (ER_STDCALL* TerUpdateGeometryProc)(ER_HND ErHandle, TErGeoHandle GeoHandle, DFRAME *KinMat);
643 
651 typedef long (ER_STDCALL* TerFreeGeometryProc)(ER_HND ErHandle, TErGeoHandle GeoHandle);
652 
662 typedef long (ER_STDCALL* TerGetActualTravelRangesProc)(ER_HND ErHandle, Host_HND HostHandle, double *Joints, double *TravelRangeMin, double *TravelRangeMax);
663 
672 typedef long (ER_STDCALL* TerNotifyProc)(ER_HND ErHandle,Host_HND HostHandle, TErNotifyData *p_NotifyData, TErExtraData ExtraData);
673 
681 typedef long (ER_STDCALL* TerGrpSyncProc)(ER_HND ErHandle,Host_HND HostHandle, TErGrpSyncData *p_GrpSyncData);
682 
683 const long JNT_TYPE_ROT =0;
684 const long JNT_TYPE_TRANS =1;
685 
686 const long JNT_DIRECTION_X = 1;
687 const long JNT_DIRECTION_Y = 2;
688 const long JNT_DIRECTION_Z = 3;
689 
690 const long JNT_CHAIN_TYPE_CHAIN = 1;
691 const long JNT_CHAIN_TYPE_NO_CHAIN = 2;
693 
694 const long IPO_MODE_BASE =0;
695 const long IPO_MODE_TOOL =1;
696 
697 // Return code for inverse kinematics, INV_WARN_*
698 const int INV_WARN_ERROR =-1;
699 const int INV_WARN_OK =0;
700 const int INV_WARN_SINGULAR =1;
701 const int INV_WARN_UNREACH =2;
702 const int INV_WARN_CNFG =3;
703 const int INV_WARN_NO_INVKIN =4;
704 const int INV_WARN_SWE_EXCEED =5;
705 
706 // Return code erGetBackLink() obsolete -> use erGetBacklink(...)
707 const long KIN_BACK_LINK_NO =0;
708 const long KIN_BACK_LINK_YES =1;
709 const long KIN_BACK_LINK_UNKNOWN =2;
710 
711 const long KIN_A2A3_COUPLING_NO =0;
712 const long KIN_A2A3_COUPLING_YES =1;
714 
715 const long KIN_COUNTER_WEIGHT_NO =0;
716 const long KIN_COUNTER_WEIGHT_YES =1;
718 
719 const long ER_ONOFF_DISABLE = 0;
720 const long ER_ONOFF_ENABLE = 1;
721 const long ER_ONOFF_STATUS = 2;
722 
723 // rotation Indices ER_ROT_
724 const long ER_ROT_IDENT = 0;
725 const long ER_ROT_X = 1;
726 const long ER_ROT_Y = 2;
727 const long ER_ROT_Z = 3;
728 
729 const long ER_ROT_XYZ = 1;
730 const long ER_ROT_ZYX = 2;
731 const long ER_ROT_YXZ = 3;
732 const long ER_ROT_ZYZ = 4;
733 const long ER_ROT_XYX = 5;
734 const long ER_ROT_RPY = 6;
735 const long ER_ROT_QUAT = 7;
736 const long ER_ROT_CA = 8;
737 const long ER_ROT_ZYpZ = 9;
738 const long ER_ROT_Y9XZ = 10;
739 const long ER_ROT_Z9XY = 11;
740 const long ER_ROT_Z9XZ = 12;
741 const long ER_ROT_Z9YX = 13;
742 const long ER_ROT_IJK = 14;
743 const long ER_ROT_ANGLE_1 = 15;
744 
745 // ERK_CAPI_SIM_COLLISION
746 const long ER_COLL_QUERY_TYPE_UNDEF = 0;
750 
751 const int ER_COLL_ALL_CONTACTS = 1;
752 const int ER_COLL_FIRST_CONTACT = 2;
753 
754 const int ER_COLL_OK = 0;
760 const int ER_COLL_ERROR = 1;
761 const int ER_COLL_HND_INVALID = 2;
762 const int ER_COLL_DETECTED = 3;
763 
768 {
769  int id1;
770  int id2;
771 };
776 {
780  long num_pairs;
782 };
783 
791 {
794  double rel_err;
795  double abs_err;
796  double distance;
797  double *p1;
798  double *p2;
799 };
800 
805 {
809  double tolerance;
810  double distance;
811  double *p1;
812  double *p2;
813 };
814 
815 //-------------------------------------------------------------------------------------------
816 // class ERK_CAPI_AUTOPATH
817 //-------------------------------------------------------------------------------------------
818 
819 const double AUTOPATH_SDK_KIN_EPSI = 0.5e-6;
820 const int AUTOPATH_SDK_KIN_DOFS = 24;
821 
822 const int AUTOPATH_SDK_AXIS_BIT_ALL = 0x0;
823 const int AUTOPATH_SDK_AXIS_BIT_1 = 0x1;
824 const int AUTOPATH_SDK_AXIS_BIT_2 = 0x2;
825 const int AUTOPATH_SDK_AXIS_BIT_3 = 0x4;
826 const int AUTOPATH_SDK_AXIS_BIT_4 = 0x8;
827 const int AUTOPATH_SDK_AXIS_BIT_5 = 0x10;
828 const int AUTOPATH_SDK_AXIS_BIT_6 = 0x20;
829 const int AUTOPATH_SDK_AXIS_BIT_7 = 0x40;
830 const int AUTOPATH_SDK_AXIS_BIT_8 = 0x80;
831 const int AUTOPATH_SDK_AXIS_BIT_9 = 0x100;
832 const int AUTOPATH_SDK_AXIS_BIT_10 = 0x200;
833 const int AUTOPATH_SDK_AXIS_BIT_11 = 0x400;
834 const int AUTOPATH_SDK_AXIS_BIT_12 = 0x800;
835 const int AUTOPATH_SDK_AXIS_BIT_13 = 0x1000;
836 const int AUTOPATH_SDK_AXIS_BIT_14 = 0x2000;
837 const int AUTOPATH_SDK_AXIS_BIT_15 = 0x4000;
838 const int AUTOPATH_SDK_AXIS_BIT_16 = 0x8000;
839 const int AUTOPATH_SDK_AXIS_BIT_17 = 0x10000;
840 const int AUTOPATH_SDK_AXIS_BIT_18 = 0x20000;
841 const int AUTOPATH_SDK_AXIS_BIT_19 = 0x40000;
842 const int AUTOPATH_SDK_AXIS_BIT_20 = 0x80000;
843 const int AUTOPATH_SDK_AXIS_BIT_21 = 0x100000;
844 const int AUTOPATH_SDK_AXIS_BIT_22 = 0x200000;
845 const int AUTOPATH_SDK_AXIS_BIT_23 = 0x400000;
846 const int AUTOPATH_SDK_AXIS_BIT_24 = 0x800000;
847 const int AUTOPATH_SDK_AXIS_BIT_DOF6 = 0x3F;
848 
849 const int AUTOPATH_SDK_OK = 0;
850 const int AUTOPATH_SDK_ERROR = 1;
852 const int AUTOPATH_SDK_ERROR_VALUE = -1;
853 
863 
867 
873 
876 const int AUTOPATH_SDK_RESULT_CPS = 3;
884 
888 
902 
903 const int AUTOPATH_SDK_STATUS_MP_START = 0x1000;
904 const int AUTOPATH_SDK_STATUS_MP_ABORT = 0x2000;
905 const int AUTOPATH_SDK_STATUS_MP_SUCCESS = 0x4000;
906 const int AUTOPATH_SDK_STATUS_MP_FAILURE = 0x8000;
907 const int AUTOPATH_SDK_STATUS_MP_IDLE = 0x10000;
908 const int AUTOPATH_SDK_STATUS_MP_RUNNING = 0x20000;
911 
912 //---------------------------------------------------------------
913 
914 typedef double ER_REAL_TYPE;
915 
916 const int AUTOPATH_SDK_AXIS_ROT = 0;
917 const int AUTOPATH_SDK_AXIS_TRANS = 1;
918 
920 {
921  unsigned int size;
923  int apHandle;
925 
926  int nConfig;
927  INT_PTR* deviceHandle;
929  int* AxisEnable;
932  int* AxisType;
939  UINT Accuracy;
940  void *UsrData;
942 
943 #endif
944 
945 
ER_REAL_TYPE * ConstraintMin
minimum constraint value, size nConfig
Definition: erk_capi_types.h:933
unsigned int * ER_HND
unique Kinematics handle, created with erInitKin()
Definition: erk_capi_types.h:195
const long ER_GRPSYNC_SET_OV_SPEED_RED
MoveSync, set current ov resulted from speed reduction.
Definition: erk_capi_types.h:342
const int ER_COLL_DETECTED
Result if Collision detected erColl_ChkCollision()
Definition: erk_capi_types.h:762
const long ER_COLL_QUERY_TYPE_COLLIDE
detects collision between two PQP_Models, erColl_ChkCollision()
Definition: erk_capi_types.h:747
const long ER_NOTIFY_CODE_WARN_SWE_EXCEED
Code notify warning, location ok but travel ranges are exceeded.
Definition: erk_capi_types.h:302
const long ER_FLYBY_TYPE_DISTANCE
Flyby by distance [mm].
Definition: erk_capi_types.h:464
const long ER_ONOFF_DISABLE
disable flag
Definition: erk_capi_types.h:719
const long ER_NOTIFY_CODE_IPO_EXEC_NOT_POSSIBLE
Code notify error -68, Cannot calculate next step.
Definition: erk_capi_types.h:318
long ExternalTcp
IPO_MODE_BASE - enabled, IPO_MODE_TOOL - disabled
Definition: erk_capi_types.h:542
DFRAME CartPosVia
Target cartesian via position for cartesian motion ER_CIRC.
Definition: erk_capi_types.h:485
const long ER_GEO_TYPE_WEDGE
Geometry Type WEDGE, number of parameter = 7: X-length [m], Y-length [m], Height [m],...
Definition: erk_capi_types.h:221
Homogeneous 4x4 transformation matrix, a Frame with 3x3 orthogonal noa-matrix (n = o x a) and 3x1 pos...
Definition: erk_capi_types.h:87
const int ER_MOP_GNT_OK_SUCCESS
Get Next Target, OK, next target available and valid.
Definition: erk_capi_types.h:580
const long ER_ROT_ZYpZ
Rotation Index: RotZ*RotY*RotZ b+m T1 xx8xx, Y >0 ist [0...180], COMAU C4G, Euler,...
Definition: erk_capi_types.h:737
const long ER_EVENT_CONDITION_UNDEF
event condition for binary input is undefined
Definition: erk_capi_types.h:604
const int AUTOPATH_SDK_ALGORITHM_RRT_CONNECT
Path Planner Algorithm: 2-RRT Connect (rapidly exploring random trees)
Definition: erk_capi_types.h:865
const long ER_ROT_X
Rotation Index: Rotation about x axis, erMath_Frame_Rot()
Definition: erk_capi_types.h:725
const long ER_MAXSTR
Maximum length of a short message.
Definition: erk_capi_types.h:102
const long ER_GRPSYNC_GET_SYNC_DISCRETE
ProcSync, aks status for SyncIDDiscrete.
Definition: erk_capi_types.h:338
unsigned int * ER_TARGET_MOVE_CP_HND
unique Target data for CP Move handle
Definition: erk_capi_types.h:210
const double ER_DEG
Conversion from radiant to degree.
Definition: erk_capi_types.h:108
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:681
ER_REAL_TYPE * ConstraintMax
maximum constraint value, size nConfig
Definition: erk_capi_types.h:934
double * p2
position at model 2 for shortest distance if minimum distance>0
Definition: erk_capi_types.h:812
const long ER_GEO_TYPE_PYRAMID
Geometry Type PYRAMID, number of parameter = 5: X-length [m], Y-length [m], Height [m],...
Definition: erk_capi_types.h:220
const int AUTOPATH_SDK_CHK_CONSTRAINT_START
action parameter is StartPose for callback fct SetCallback_CheckConstraints()
Definition: erk_capi_types.h:890
ER_REAL_TYPE * DistanceWeight
]0..1], size nConfig, currently not used
Definition: erk_capi_types.h:938
ER_CollisionPair * pairs
array of collided triangle pairs if num_pairs > 0
Definition: erk_capi_types.h:781
const long ER_OUPUT_FORMAT_W_ORIENTATION
desired output_format for erGET_NEXT_STEP is Cartesian ( w/orientation )
Definition: erk_capi_types.h:383
const int ER_COLL_OK
Used by all API routines upon successful completion except.
Definition: erk_capi_types.h:754
const long JNT_TYPE_TRANS
Robot Joint is prismatic.
Definition: erk_capi_types.h:684
const int ER_COLL_ERR_BUILD_EMPTY_MODEL
Returned when erColl_EndModel() is called on a model to which no triangles have been added....
Definition: erk_capi_types.h:759
const long IPO_MODE_BASE
Interpolation mode is w.r.t. BASE (work object)
Definition: erk_capi_types.h:694
const long ER_NOTIFY_DOMAIN_MOTION_EXEC
Domain notify level: MOTION_EXEC 401-500 Get_Next_Step.
Definition: erk_capi_types.h:294
const long ER_OUPUT_FORMAT_JOINT_ANGLE_DIST
desired output_format for erGET_NEXT_STEP is Joint angle/distance
Definition: erk_capi_types.h:382
ER_EXTAX_KIN_DATA extax_data[ER_EXTAX_KIN_DATA_MAX]
external axis data
Definition: erk_capi_types.h:450
const int INV_WARN_OK
inverse kinematics calculation successful "OK", target location is reachable
Definition: erk_capi_types.h:699
const long ER_NOTIFY_CODE_IPO_MOTYPE_NOT_SUPPORTED
Code notify, error -17, specified motion type is not supported.
Definition: erk_capi_types.h:310
double speed_ori_value
Speed for the orientation during cartesian motion [rad/sec].
Definition: erk_capi_types.h:477
const int AUTOPATH_SDK_AXIS_BIT_DOF6
axisBit Axis 1..6
Definition: erk_capi_types.h:847
DFRAME m1Tm2
DFRAME transformation from model 1 to model 2
Definition: erk_capi_types.h:793
const long IPO_MODE_TOOL
Interpolation mode is w.r.t. external TCP.
Definition: erk_capi_types.h:695
#define ER_STDCALL
Definition: erk_capi_types.h:78
const long KIN_A2A3_COUPLING_UNKNOWN
Robot has no informaton about axis coupling between axis 2 and 3.
Definition: erk_capi_types.h:713
long SyncOvSpeedReduceDiscrete
Synchronized Override Discrete 0 - stopp motion , 1 - continue motion.
Definition: erk_capi_types.h:546
const int ER_GEO_ATTRIBUTES_BBWIRE
GeoAttributes render bbox wire, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:235
const int AUTOPATH_SDK_AXIS_BIT_23
axisBit Axis 23
Definition: erk_capi_types.h:845
const long ER_ROT_QUAT
Rotation Index: Quaternion, ABB, erMath_VecToFrameIdx(), erMath_FrameToVecIdx.
Definition: erk_capi_types.h:735
const long ER_CSTEP_STATUS_UNDEF
current step status is not defined, erGetCurrentStepData()
Definition: erk_capi_types.h:512
Definition: erk_capi_types.h:442
const long ER_NOTIFY_CODE_WARN_NO_INVKIN
Code notify error, device has no inverse kinematics.
Definition: erk_capi_types.h:301
double SyncOvSpeedReduceContinuous
Synchronized Override resulted from automated Speed Reduction Continuous [0..1].
Definition: erk_capi_types.h:547
const long ER_EVENT_BOOL_ON
Event status for binary input/output events is ON.
Definition: erk_capi_types.h:598
int * AxisEnable
1-enabled, 0-disabled, size nConfig
Definition: erk_capi_types.h:929
const int ER_MOP_GNS_TOOLPATH_REACHED
Get Next Step, Final step, last toolpath target reached.
Definition: erk_capi_types.h:591
const int AUTOPATH_SDK_AXIS_BIT_17
axisBit Axis 17
Definition: erk_capi_types.h:839
const long ER_NOTIFY_CODE_WARN_CONFIG_INVALID
Code notify error, invalid configuration.
Definition: erk_capi_types.h:300
const long ER_KIN_PASSIVE_JNTS
Maximum number of passive joints for a kinematics.
Definition: erk_capi_types.h:96
const int ER_MOP_GNS_OK_SUCCESS
Get Next Step, OK, next step is calculated successful.
Definition: erk_capi_types.h:588
const long ER_TARGET_TYPE_ABSJOINT
Target single axis motion,if motion_type = JOINT --> AbsJoint.
Definition: erk_capi_types.h:379
const int ER_MOP_GNS_ERROR
Get Next Step, Error.
Definition: erk_capi_types.h:587
long num_pairs
number of collided triangle pairs
Definition: erk_capi_types.h:780
const int AUTOPATH_SDK_CHK_CONSTRAINT_TBD_200
action parameter is tbd
Definition: erk_capi_types.h:899
const int ER_MOP_GNT_NO_TARGETS
Get Next Target,.
Definition: erk_capi_types.h:581
const int AUTOPATH_SDK_STATUS_MP_ABORT
AutoPath calculation aborted.
Definition: erk_capi_types.h:904
double query_time_secs
required time for collision computation
Definition: erk_capi_types.h:792
const int AUTOPATH_SDK_AXIS_BIT_ALL
axisBit Axis all
Definition: erk_capi_types.h:822
const int AUTOPATH_SDK_ALGORITHM_USER_FCT
Path Planner Algorithm: 1-User Fct.
Definition: erk_capi_types.h:864
const long ER_DOMINANT_INTERPOLATION_POS
1-dominant interpolation type, Position is master, erSELECT_DOMINANT_INTERPOLATION()
Definition: erk_capi_types.h:413
const int AUTOPATH_SDK_CHK_CONSTRAINT_ISCFREE
action parameter chk constraint for callback fct SetCallback_CheckConstraints()
Definition: erk_capi_types.h:898
const long ER_ROT_IJK
Rotation Index: Approach Axis Vector, erMath_VecToFrameIdx(), erMath_FrameToVecIdx.
Definition: erk_capi_types.h:742
double * p1
position at model 1 for shortest distance if minimum distance>0
Definition: erk_capi_types.h:811
const int AUTOPATH_SDK_INVALID_LICENSE
Error, AutoPath not licensed.
Definition: erk_capi_types.h:851
const long ER_TARGET_TYPE_ABS
Target w.r.t object frame.
Definition: erk_capi_types.h:378
const int ER_MOP_GNTPS_CNTRL_LOG_FILE
Get Next Tool Path Step, creates log file, use with ER_MOP_GNTPS_CNTRL_INIT.
Definition: erk_capi_types.h:574
const long ER_PTP_TARGET_CALC_MODE_TURNS
PTP solution calculated using turns, NEXT_TARGET_DATA.
Definition: erk_capi_types.h:401
const long ER_EVENT_TRIGGER_DWN
Signal Trigger to control binary output. DWN set output event to ER_EVENT_BOOL_OFF.
Definition: erk_capi_types.h:601
const long ER_ROT_IDENT
Rotation Index: Identity, erMath_Frame_Rot()
Definition: erk_capi_types.h:724
const long ER_TTTRRR_ID
Device modelled as 6 DOF Gantry TTT:RRR type.
Definition: erk_capi_types.h:363
long target_type
Target Type ER_TARGET_TYPE_ABS or ER_TARGET_TYPE_ABSJOINT.
Definition: erk_capi_types.h:475
const long ER_NOTIFY_CODE_IPO_EXEC_POS_OUT_OF_RANGE
Code notify error -52, cartesian position is out of work range.
Definition: erk_capi_types.h:320
const int AUTOPATH_SDK_AXIS_BIT_20
axisBit Axis 20
Definition: erk_capi_types.h:842
Collision results for query ER_COLL_QUERY_TYPE_TOLERANCE, see erColl_GetResults_Tolerance()
Definition: erk_capi_types.h:804
double bending_angle_value
Bending angle [rad].
Definition: erk_capi_types.h:482
const double ER_RAD
Conversion from degree to radiant.
Definition: erk_capi_types.h:109
ER_REAL_TYPE * CartConstraintMax
maximum cartesian constraint value, size ER_DIM
Definition: erk_capi_types.h:936
const int AUTOPATH_SDK_AXIS_ROT
Axis is rotational.
Definition: erk_capi_types.h:916
const long ER_LICENSE_PRIORITY_LOCAL
check local license first
Definition: erk_capi_types.h:275
long axis_idx
axis idx of controlled joint for connected device [0..ER_EXTAX_KIN_DATA_MAX-1]
Definition: erk_capi_types.h:430
long ptp_target_calculation_mode
PTP target calculation mode, ER_PTP_TARGET_CALC_MODE_SHORTEST_ANGLE, ER_PTP_TARGET_CALC_MODE_TURNS,...
Definition: erk_capi_types.h:455
const int AUTOPATH_SDK_OK
AutoPath method successful.
Definition: erk_capi_types.h:849
const int ER_MOP_GNTPS_CNTRL_UNDEF
Get Next Tool Path Step, undefined request.
Definition: erk_capi_types.h:566
double JointPos[ER_KIN_DOFS]
current joint position [rad,mm]
Definition: erk_capi_types.h:532
const long ER_NOTIFY_TYPE_INTERNAL_ERROR
Notify Type Level: Initial ERROR 3.
Definition: erk_capi_types.h:287
const long ER_NOTIFY_DOMAIN_FILE_IO
Domain notify level: FILE_IO 101-200.
Definition: erk_capi_types.h:291
const long ER_DOMINANT_INTERPOLATION_ORI
2-dominant interpolation type, Orientation is master, erSELECT_DOMINANT_INTERPOLATION()
Definition: erk_capi_types.h:414
const long ER_ROT_ANGLE_1
Rotation Index: One Axis Angle Rotation, erMath_VecToFrameIdx(), erMath_FrameToVecIdx.
Definition: erk_capi_types.h:743
TErTargetID TargetID
Target ID where the notification occured, Default 0.
Definition: erk_capi_types.h:333
int initialized
1- structure is completely initialized, 0- not initialized
Definition: erk_capi_types.h:922
const long ER_SLEW
Motion Type SLEW, Async PTP or AbsJoint, erSELECT_MOTION_TYPE()
Definition: erk_capi_types.h:396
unsigned int * ER_TARGET_EXTAX_DEVICE_POSITIONER_HND
unique External axis data definition for Positioner/TurnTable handle
Definition: erk_capi_types.h:213
long n_dof
number of manipulator joints
Definition: erk_capi_types.h:531
int * deviceAxisIdx
Device Index of Axis, size nConfig.
Definition: erk_capi_types.h:928
const long ER_FLYBY_OFF
Flyby OFF, disabled.
Definition: erk_capi_types.h:459
const int ER_MOP_GNTPS_CNTRL_STEPDATA_OUT
Get Next Tool Path Step, writes current StepData into dat stream, use with ER_MOP_GNTPS_CNTRL_NEXT_ST...
Definition: erk_capi_types.h:577
const int AUTOPATH_SDK_AXIS_BIT_16
axisBit Axis 16
Definition: erk_capi_types.h:838
const long ER_DMAXSTR
Maximum length of a medium message.
Definition: erk_capi_types.h:103
const long ER_RRRRRR_BL_ID
Device modelled as fixed articulated RRR:RRR type with back link, such as an ABB IRB-1400.
Definition: erk_capi_types.h:364
const long ER_DH_ID
Device modelled with DH Denavit-Hartenberg-Transformation.
Definition: erk_capi_types.h:366
long SyncType
0-ER_GRPSYNC_GET_SYNC_DISCRETE 1-ER_GRPSYNC_SET_DURATION 2-ER_GRPSYNC_GET_DURATION_MAX 3-ER_GRPSYNC_G...
Definition: erk_capi_types.h:349
const long ER_NOTIFY_CODE_WARN_ERROR
Code notify error, ERROR.
Definition: erk_capi_types.h:303
const long ER_NOTIFY_CODE_IPO_PREP_INVALID_CHANGE_OF_TRACKING_BASE
Code notify, error -76 , Direkter Wechsel von einem Tracking Base zum anderem nicht möglich....
Definition: erk_capi_types.h:313
const long JNT_CHAIN_TYPE_CHAIN
Robot Joint is in the kinematics chain.
Definition: erk_capi_types.h:690
double LagWaitTime
Lag time, after robot reaches its target.
Definition: erk_capi_types.h:452
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:642
const long ER_NOTIFY_CODE_IPO_PREP_ERROR
Code notify, praparation failed,internal error -68.
Definition: erk_capi_types.h:308
const long TRK_WND_OUT_OF_BOUNDARY
Robot outside tracking window boundary = 3;.
Definition: erk_capi_types.h:492
double SyncOvTrajScale
Synchronized Override resulted from Trajectory scaling [0..1].
Definition: erk_capi_types.h:548
const long ER_EVENT_CONDITION_WAIT_DIN_LT
event condition for binary input, wait until DIN is less than given value
Definition: erk_capi_types.h:609
const long ER_CSTEP_STATUS_WAIT_FOR_TRACKING_WINDOW
current step status Wait for Tracking Window
Definition: erk_capi_types.h:516
long TrackingWindowStatus
tracking window status, TRK_WND_NOT_ACTIVE, TRK_WND_WAITING, TRK_WND_INSIDE, TRK_WND_OUT_OF_BOUNDARY
Definition: erk_capi_types.h:509
double TrajectoryTime
Output: Calculated trajectory time in [sec].
Definition: erk_capi_types.h:449
const int ER_COLL_HND_INVALID
Error, invalid collision handle.
Definition: erk_capi_types.h:761
const int AUTOPATH_SDK_CHK_CONSTRAINT_TBD_80
action parameter is tbd
Definition: erk_capi_types.h:897
const long ER_GEO_TYPE_CYLINDER
Geometry Type CYLINDER, number of parameter = 9: Radius [deg], Height_1 [m], y-Scale,...
Definition: erk_capi_types.h:222
double TrajectoryTimeRemaining
current remaining time for the returned step, if 0, target reached
Definition: erk_capi_types.h:553
struct _ER_EXTAX_KIN_DATA ER_EXTAX_KIN_DATA
TErTargetID TargetID
Identifier of the target, 0 no identifier givin, >0 identifier of this target.
Definition: erk_capi_types.h:443
const int AUTOPATH_SDK_AXIS_BIT_8
axisBit Axis 8
Definition: erk_capi_types.h:830
const int INV_WARN_NO_INVKIN
ERROR kinematics has no inverse kinematics defned.
Definition: erk_capi_types.h:703
double distance
minimum distance>0 if models not colliding, else distance is 0
Definition: erk_capi_types.h:810
const long ER_NOTIFY_CODE_IPO_PREP_INVALID_IPO_WHILE_TRACKING
Code notify, error -76, PTP/ABS-Joint Interpolation in einer koordinierten Bewegung (Tracking) nicht ...
Definition: erk_capi_types.h:312
const long ER_UNIV_ROB_ID
Device modelled with universal coordinates.
Definition: erk_capi_types.h:365
const long ER_ROT_Y9XZ
Rotation Index: RotY*RotX*RotZ,b+m T1 xx7xx, [-90..+90] [-180..+180] [-180..+180] (~BOSCH),...
Definition: erk_capi_types.h:738
const int AUTOPATH_SDK_PARAMETER_THREAD_EXECUTION
Enables Thread Execution: 1-on, 0-off.
Definition: erk_capi_types.h:861
const int AUTOPATH_SDK_AXIS_BIT_13
axisBit Axis 13
Definition: erk_capi_types.h:835
const int ER_GEO_ATTRIBUTES_OBJ_MEM_MODEL_VBO
GeoAttributes geometry object memory model 1-OBJ_MEM_VBO, 0-OBJ_MEM_GRAHICS or OBJ_MEM_NATIVE_CPU,...
Definition: erk_capi_types.h:247
const int AUTOPATH_SDK_ALGORITHM_RTD_BBS
Path Planner Algorithm: 3-RTD BBS.
Definition: erk_capi_types.h:866
unsigned int * ER_TARGET_LOCATION_HND
unique Target location handle, created with erAddTargetLocation()
Definition: erk_capi_types.h:203
double JointPos[ER_KIN_DOFS]
Target joint position.
Definition: erk_capi_types.h:446
const int AUTOPATH_SDK_RESULT_QUALITY_INDEX_STD_DEV
Quality Index Standard Deviation, based on calculated way points.
Definition: erk_capi_types.h:883
const int ER_MOP_GNT_ERROR
Get Next Target, Error.
Definition: erk_capi_types.h:579
double segment_length
Segment length to Target location [m].
Definition: erk_capi_types.h:479
const long KIN_COUNTER_WEIGHT_YES
Robot has a counter weight.
Definition: erk_capi_types.h:716
int ThreadedExecution
1-Thread, 0-no Thread, direct function call
Definition: erk_capi_types.h:924
const long ER_GEO_TYPE_3DS
Geometry Type 3DS file, number of scaling = 3: X-, Y-, Z-scale, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:227
const long ER_DOF9
9 Degrees-of-Freedom
Definition: erk_capi_types.h:99
const long ER_OUPUT_FORMAT_JOINT_ENCODER
desired output_format for erGET_NEXT_STEP is Joint encoder
Definition: erk_capi_types.h:381
const int AUTOPATH_SDK_PARAMETER_LIMIT_REVOLUTE_JNT_CSPACE
Limit revolute joints in C-Space: 1-on, 0-off.
Definition: erk_capi_types.h:859
const long ER_OUPUT_FORMAT_CART_JOINT_ENCODER
desired output_format for erGET_NEXT_STEP is Cartesian and joint encoder
Definition: erk_capi_types.h:384
const int AUTOPATH_SDK_RESULT_CFREE
Number of CFree Checks during AutoPath calculation.
Definition: erk_capi_types.h:877
const long ER_PTP_TARGET_CALC_MODE_MATH
PTP solution calculated mathematical [-180, 180], NEXT_TARGET_DATA.
Definition: erk_capi_types.h:402
const long ER_PTP
Motion Type JOINT or PTP, Synchro PTP or AbsJoint, erSELECT_MOTION_TYPE()
Definition: erk_capi_types.h:394
void(ER_STDCALL * TerLogProc)(long LogType, char *LogMessage)
Callback function type definition for Log messages, erSetCallBack_LogProc()
Definition: erk_capi_types.h:626
const long ER_SYNC_OFF_TRACKING_WINDOWS_ON
device synchronization OFF while Tracking Window active, tbd
Definition: erk_capi_types.h:360
const long ER_JOINT
Motion Type JOINT or PTP, Synchro PTP or AbsJoint, erSELECT_MOTION_TYPE()
Definition: erk_capi_types.h:393
DFRAME * GeoMat
location of geometry w.r.t. to belonging axis ax_idx
Definition: erk_capi_types.h:263
const long ER_HS_MAXSTR
Maximum length of a huge message.
Definition: erk_capi_types.h:105
const long KIN_BACK_LINK_UNKNOWN
Robot has no informaton about Backlink.
Definition: erk_capi_types.h:709
const int ER_COLL_ERROR
Error, kernel not initialized or option not licensed.
Definition: erk_capi_types.h:760
const long ER_GRPSYNC_GET_DURATION_MAX
MoveSync, get max duration of motion times of all robots in KIR group.
Definition: erk_capi_types.h:340
double TrajectoryTime_nominal
nominal calculated trajectory time in [sec]
Definition: erk_capi_types.h:550
const long ER_ROT_YXZ
Rotation Index: RotY*RotX*RotZ, BOSCH, erMath_VecToFrameIdx(), erMath_FrameToVecIdx.
Definition: erk_capi_types.h:731
long GeoType
Type of geometry, one of ER_GEO_TYPE_CUBE, ER_GEO_TYPE_PYRAMID, ER_GEO_TYPE_WEDGE,...
Definition: erk_capi_types.h:265
const int AUTOPATH_SDK_PARAMETER_FORCE_DETERM_BEHAVIOR
Force deterministic behavior: 1-on, 0-off.
Definition: erk_capi_types.h:858
long turn_value[ER_KIN_DOFS]
Target turn values if ER_PTP_TARGET_CALC_MODE_TURNS is enabled.
Definition: erk_capi_types.h:456
const int ER_MOP_GNTPS_CNTRL_INIT
Get Next Tool Path Step, Initialize ToolPath interpolation.
Definition: erk_capi_types.h:567
double OverrideSpeed
Programmed Speed Override [0..100%].
Definition: erk_capi_types.h:545
const int ER_APIDLL_CNTRL_SIM_STEP
Calling status for API-DLL, Cycle indicates one simulation step or simulation cycle within a simulati...
Definition: erk_capi_types.h:117
const int ER_MOP_GNTPS_CNTRL_PRG_FILE
Get Next Tool Path Step, creates prg file, use with ER_MOP_GNTPS_CNTRL_INIT.
Definition: erk_capi_types.h:575
struct _AutoPath_ConfigurationSpace AutoPath_ConfigurationSpace
const long ER_NOTIFY_DOMAIN_OK
Domain notify level: OK 0.
Definition: erk_capi_types.h:289
const int AUTOPATH_SDK_KIN_DOFS
Maximum number of configuration space (Degrees-of-Freedom for a kinematics)
Definition: erk_capi_types.h:820
const int AUTOPATH_SDK_STATUS_MP_RUNNING
AutoPath in process.
Definition: erk_capi_types.h:908
int * AxisType
one of AUTOPATH_SDK_AXIS_TYPE_ROBOT, AUTOPATH_SDK_AXIS_TYPE_TRACK, AUTOPATH_SDK_AXIS_TYPE_POSITIONER,...
Definition: erk_capi_types.h:932
const int AUTOPATH_SDK_AXIS_BIT_14
axisBit Axis 14
Definition: erk_capi_types.h:836
double ER_REAL_TYPE
Definition: erk_capi_types.h:914
int id1
identifier triangles 1st object
Definition: erk_capi_types.h:769
const long ER_NOTIFY_DOMAIN_MOTION_PREP
Domain notify level: MOTION_PREP 301-400 Set_Next_Target.
Definition: erk_capi_types.h:293
double * Scaling
xyz scaling of loaded geometry and depending on GeoType
Definition: erk_capi_types.h:262
const long ER_NOTIFY_CODE_IPO_PREP_CONFIG
Code notify, warning Cannot change configuration during LIN or CIRC move.
Definition: erk_capi_types.h:309
const int AUTOPATH_SDK_AXIS_TYPE_POSITIONER
Axis Type External Positioner axis.
Definition: erk_capi_types.h:870
const long JNT_DIRECTION_X
Robot Joint is in X direction.
Definition: erk_capi_types.h:686
const int AUTOPATH_SDK_STATUS_MP_MIN_NUM_WAYPOINTS
AutoPath minimize number of WayPoint.
Definition: erk_capi_types.h:909
const long ER_ROT_XYX
Rotation Index: RotX*RotY*RotX, erMath_VecToFrameIdx(), erMath_FrameToVecIdx.
Definition: erk_capi_types.h:733
const long ER_SYNC_ON
device synchronization ON
Definition: erk_capi_types.h:357
const int ER_GEO_ATTRIBUTES_FLAT
GeoAttributes render flat, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:238
const int AUTOPATH_SDK_AXIS_BIT_11
axisBit Axis 11
Definition: erk_capi_types.h:833
const long ER_NOTIFY_CODE_IPO_EXEC_SPEED_REDUCE_START
Code notify warning, Start Speed reduction.
Definition: erk_capi_types.h:315
Definition: erk_capi_types.h:525
double rel_err
the relative error margin from actual distance
Definition: erk_capi_types.h:794
Collision results for query ER_COLL_QUERY_TYPE_COLLIDE, see erColl_GetResults_Collide() .
Definition: erk_capi_types.h:775
const int AUTOPATH_SDK_AXIS_BIT_15
axisBit Axis 15
Definition: erk_capi_types.h:837
const int INV_WARN_SINGULAR
Warning: Target location is reachable, but location is in singularity.
Definition: erk_capi_types.h:700
const long ER_SPEED_REDUCTION_DISABLE
Speed reduction is disabled.
Definition: erk_capi_types.h:391
const long ER_EVENT_TRIGGER_UP
Signal Trigger to control binary output. UP set output event to ER_EVENT_BOOL_ON.
Definition: erk_capi_types.h:602
const int AUTOPATH_SDK_PARAMETER_ALGORITHM
Selected Path Planner Algorithm: 1-User Fct, 2-RRT Connect, 3-RTD BBS.
Definition: erk_capi_types.h:855
const long ER_DOMINANT_INTERPOLATION_AUTO
4-dominant interpolation type, Automatic (the slowest one is leading), erSELECT_DOMINANT_INTERPOLATIO...
Definition: erk_capi_types.h:416
char Configuration[ER_MAXSTR]
Manipulator configuration string.
Definition: erk_capi_types.h:501
const long ER_CSTEP_STATUS_OK
current step status is OK, erGetCurrentStepData()
Definition: erk_capi_types.h:514
unsigned int * ER_TARGET_EXTAX_DEVICE_TRACKMOTION_HND
unique External axis data definition for Track/Slider handle
Definition: erk_capi_types.h:212
const long KIN_BACK_LINK_NO
Robot has no Backlink.
Definition: erk_capi_types.h:707
const int ER_EVENT_BOOL_N
Number of boolean events for binary inputs/outputs.
Definition: erk_capi_types.h:594
const int INV_WARN_UNREACH
inverse kinematics calculation failed, target location is unreachable
Definition: erk_capi_types.h:701
const long ER_GEO_TYPE_STL
Geometry Type STL ascii or binary file, number of scaling = 3: X-, Y-, Z-scale, see LOAD_GEOMETRY_DAT...
Definition: erk_capi_types.h:226
const int AUTOPATH_SDK_CHK_CONSTRAINT_UNDEF
action parameter is undefined for callback fct SetCallback_CheckConstraints()
Definition: erk_capi_types.h:889
const long ER_CSTEP_STATUS_ERROR
current step status is ERROR, erGetCurrentStepData()
Definition: erk_capi_types.h:513
struct _NEXT_TARGET_DATA NEXT_TARGET_DATA
const int AUTOPATH_SDK_AXIS_BIT_4
axisBit Axis 4
Definition: erk_capi_types.h:826
double TrajectoryTimeDelay
current trajectory time delay, >0 in case robot speed reductions
Definition: erk_capi_types.h:554
const int ER_GEO_ATTRIBUTES_SHOW_MESH
GeoAttributes geometry visualized meshes, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:243
long flyby_type
Flyby Type ER_FLYBY_TYPE_UNDEF = 0, ER_FLYBY_TYPE_SPEED = 1, ER_FLYBY_TYPE_DISTANCE = 2.
Definition: erk_capi_types.h:480
long get_nxt_step_result
current step status, get next step result 0-Ok, 1-need more data, 2-final step, target reached,...
Definition: erk_capi_types.h:527
const int ER_GEO_ATTRIBUTES_SHOW_EDGES
GeoAttributes geometry visualized edges, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:244
const long ER_MOTION_FILTER_GEO
Motion filter set to geometric velocity profile, erSET_MOTION_FILTER()
Definition: erk_capi_types.h:387
long GeoSizeParameterNum
Number of geometry primitive parameter in GeoSizeParameter, depending on loaded GeoType.
Definition: erk_capi_types.h:267
const int AUTOPATH_SDK_PARAMETER_THREAD_PRIORITY
Thread priority: 0-normal, 1-low, 2-high.
Definition: erk_capi_types.h:860
const long ER_FLYBY_TYPE_SPEED
Flyby by speed [%].
Definition: erk_capi_types.h:463
const int ER_GEO_ATTRIBUTES_SMOOTH
GeoAttributes render smooth, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:232
const int ER_MOP_GNTPS_CNTRL_NEXT_STEP
Get Next Tool Path Step, Calculate one interpolation step.
Definition: erk_capi_types.h:569
const int ER_GEO_ATTRIBUTES_SHOW_NORMALS
GeoAttributes geometry visualized with normals, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:242
const long ER_NOTIFY_CODE_WARN_UNREACH
Code notify error, location unsrechable.
Definition: erk_capi_types.h:299
TErTrackingWindowID TrackingWindowID
unique tracking window identifier
Definition: erk_capi_types.h:508
unsigned int * ER_TARGET_EVENTS_HND
unique Events handle
Definition: erk_capi_types.h:206
const long ER_NOTIFY_CODE_IPO_EXEC_SPEED_REDUCE_STOP
Code notify warning, Stop Speed reduction.
Definition: erk_capi_types.h:316
const long ER_NOTIFY_CODE_WARN_SINGULAR
Code notify warning, robot in singularity.
Definition: erk_capi_types.h:298
long SyncIDDiscrete
Handle for ProcSync.
Definition: erk_capi_types.h:453
int apHandle
individual handle, currently not used
Definition: erk_capi_types.h:923
long AdvanceParam
1 valid data specified, 0 no data specified, 2 initializes and set default data
Definition: erk_capi_types.h:472
const long ER_CIRC_ORI_INTERPOLATION_FIX
Keep current orientation during interpolation on a circle, hereby the orientation in start-,...
Definition: erk_capi_types.h:422
const int ER_MOP_SNT_OK_SUCCESS
Set Next Target, OK, next target prepared successful.
Definition: erk_capi_types.h:584
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:672
const double ER_m2mm
Conversion from [mm] to [m].
Definition: erk_capi_types.h:111
const long JNT_DIRECTION_Y
Robot Joint is in Y direction.
Definition: erk_capi_types.h:687
TErTargetID TargetID
unique target identifier
Definition: erk_capi_types.h:507
char Configuration[ER_MAXSTR]
Target manipulator configuration string.
Definition: erk_capi_types.h:447
double abs_err
the absolute error margin from actual distance
Definition: erk_capi_types.h:795
const long ER_GEO_TYPE_CUBE
Geometry Type CUBE, number of parameter = 3: X-length [m], Y-length [m], Height [m],...
Definition: erk_capi_types.h:219
const int ER_APIDLL_CNTRL_SIM_STOP
Calling status for API-DLL, Stop indicates that the simulation is aborted.
Definition: erk_capi_types.h:118
const long ER_CSTEP_STATUS_IPO_IN_POSITION
current step status Robot already in Position
Definition: erk_capi_types.h:517
unsigned int * ER_TARGET_ATTRIBUTES_HND
unique Motion attributes handle
Definition: erk_capi_types.h:208
const int AUTOPATH_SDK_RESULT_DSECONDS
Elapsed time in deciseconds (1/10) for AutoPath calculation.
Definition: erk_capi_types.h:880
const long ER_PTP_TARGET_CALC_MODE_UNDEF
default ER_PTP_TARGET_CALC_MODE_SHORTEST_ANGLE, NEXT_TARGET_DATA
Definition: erk_capi_types.h:399
const int ER_MOP_GNTPS_CNTRL_TBD_08
tbd
Definition: erk_capi_types.h:570
const int ER_GEO_ATTRIBUTES_COLL_REF_EXCL_CHILD
GeoAttributes geometry object memory model 0-GEO_COLL_REF_EXCL_UNDEF, 1-GEO_COLL_REF_EXCL_CHILD,...
Definition: erk_capi_types.h:249
double TrajectoryTime
current trajectory time
Definition: erk_capi_types.h:551
const long KIN_A2A3_COUPLING_NO
Robot has no axis coupling between axis 2 and 3.
Definition: erk_capi_types.h:711
const long ER_FLYBY_ON
Flyby ON, enabled.
Definition: erk_capi_types.h:460
DFRAME CartPos
Target cartesian position for cartesian motion or joint motion with target type ER_TARGET_TYPE_ABS.
Definition: erk_capi_types.h:484
const int AUTOPATH_SDK_AXIS_BIT_10
axisBit Axis 10
Definition: erk_capi_types.h:832
const long ER_GEO_PARAMETER_MAX
Maximum number of reserved geometry parameter, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:229
long n_dof_external
number of external manipulator joints
Definition: erk_capi_types.h:536
const int AUTOPATH_SDK_STATUS_MP_IDLE
AutoPath is idle.
Definition: erk_capi_types.h:907
int * AxisRotTrans
Rotary Axis = AUTOPATH_SDK_AXIS_ROT, Translatory Axis = AUTOPATH_SDK_AXIS_TRANS, size nConfig.
Definition: erk_capi_types.h:931
const long ER_MOTION_FILTER_C2
Motion filter set to c2-velocity profile, erSET_MOTION_FILTER()
Definition: erk_capi_types.h:388
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:633
int NotificationType
ER_NOTIFY_TYPE_MSG = 0; ER_NOTIFY_TYPE_WARNING = 1; ER_NOTIFY_TYPE_ERROR = 2; ER_NOTIFY_TYPE_INTERNAL...
Definition: erk_capi_types.h:330
double ElapsedTime
Output: Elapsed time for the returned step, if 0, no valid step is returned.
Definition: erk_capi_types.h:502
DFRAME CartPos
Cartesian position.
Definition: erk_capi_types.h:499
const long ER_EXTAX_KIN_DATA_MAX
Maximum number of external axis data.
Definition: erk_capi_types.h:435
const int AUTOPATH_SDK_AXIS_BIT_9
axisBit Axis 9
Definition: erk_capi_types.h:831
const int AUTOPATH_SDK_AXIS_TYPE_AUX
Axis Type Aux Axis.
Definition: erk_capi_types.h:872
External axis target data for connected devices belongs to structure NEXT_TARGET_DATA.
const long ER_LOG_TYPE_ERROR
error Log Message, callback function TerLogProc()
Definition: erk_capi_types.h:281
struct _CURRENT_STEP_DATA CURRENT_STEP_DATA
unsigned int size
sizeof this structure
Definition: erk_capi_types.h:921
long GeoAttributeParameterNum
Number of geometry attribute parameter in GeoAttributeParameter.
Definition: erk_capi_types.h:269
const int AUTOPATH_SDK_AXIS_BIT_3
axisBit Axis 3
Definition: erk_capi_types.h:825
const int AUTOPATH_SDK_RESULT_CPS
Number of Check per seconds for AutoPath calculation.
Definition: erk_capi_types.h:876
const long ER_EVENT_TRIGGER_OFF
Signal Trigger to control binary output. OFF will not set output event.
Definition: erk_capi_types.h:600
const long ER_GRPSYNC_SET_DURATION
MoveSync, set duration of calculated motion time for current move.
Definition: erk_capi_types.h:339
const long ER_CIRC_ORI_INTERPOLATION_START_END
Use start- and end-location for orientation interpolation on a circle, erSELECT_CIRCULAR_ORIENTATION_...
Definition: erk_capi_types.h:418
char * GeoName
name of loaded geometry
Definition: erk_capi_types.h:260
long TargetParam
0 unused (only position data are valid), 1 radius, 2 angle, 3 distance
Definition: erk_capi_types.h:444
const int ER_GEO_ATTRIBUTES_BBFLAT
GeoAttributes render bbox flat, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:234
DFRAME CartPos
Target cartesian position.
Definition: erk_capi_types.h:445
const long ER_NOTIFY_CODE_IPO_EXEC_AXIS_SPEED_EXCEED
Code notify warning, maximum joint speed exceeded.
Definition: erk_capi_types.h:322
const int AUTOPATH_SDK_PARAMETER_MIN_NUM_WAYPOINTS
Minimize number of WayPoints: 1-on, 0-off.
Definition: erk_capi_types.h:857
const long ER_EVENT_BOOL_UNDEF
Event status for binary input/output events is undefined.
Definition: erk_capi_types.h:596
struct _NEXT_TARGET_DATA_ADVANCE NEXT_TARGET_DATA_ADVANCE
unsigned int TErGeoHandle
unique Geometry handle used for callback functions TerLoadGeometryProc()
Definition: erk_capi_types.h:197
const long KIN_BACK_LINK_YES
Robot has a Backlink.
Definition: erk_capi_types.h:708
const int ER_GEO_ATTRIBUTES_VERTICES
GeoAttributes render vertices, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:237
const long ER_COLL_QUERY_TYPE_DISTANCE
computes the minimum distance between two PQP_Models, erColl_ChkCollision()
Definition: erk_capi_types.h:748
long GeoAttributes
Bitfield for additional geometry attributes, such as ER_GEO_ATTRIBUTES_SMOOTH, ER_GEO_ATTRIBUTES_INVE...
Definition: erk_capi_types.h:266
double TargetParamValue
= 2, for radiants
Definition: erk_capi_types.h:448
const int ER_MOP_SNT_NEED_MORE_DATA
Set Next Target, Need more data to prepare next motion.
Definition: erk_capi_types.h:585
const int AUTOPATH_SDK_ERROR_VALUE
Error in AutoPath method.
Definition: erk_capi_types.h:852
const int ER_GEO_ATTRIBUTES_SHOW_NAME
GeoAttributes geometry visualized with name, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:241
long NumberofMessages
Specifies the number of messages, tbd.
Definition: erk_capi_types.h:505
const int ER_MOP_GNTPS_CNTRL_TERMINATE
Get Next Tool Path Step, Terminate ToolPath interpolation.
Definition: erk_capi_types.h:568
const long ER_DOF_QUAT
Quaternion vector length.
Definition: erk_capi_types.h:98
long MotionType
Motion Type ER_JOINT = ER_PTP = 1, ER_LIN = 2, ER_SLEW = 3, ER_CIRC = 4.
Definition: erk_capi_types.h:474
const int AUTOPATH_SDK_PARAMETER_DYNADJUST
Dynamic adjust Accuracy: 1-on, 0-off.
Definition: erk_capi_types.h:854
DFRAME CartPosRBase
current cartesian TCP position w.r.t. Robot Base
Definition: erk_capi_types.h:530
const int ER_GEO_ATTRIBUTES_CHK_COLLISION
GeoAttributes geometry in collision queue, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:246
const int ER_MOP_GNS_NEED_MORE_DATA
Get Next Step, Final step, target reached.
Definition: erk_capi_types.h:589
const long ER_NOTIFY_CODE_FIND_CONFIG_FAILED
Code notify error, cannot find a valid configuration.
Definition: erk_capi_types.h:304
int nConfig
complete configuration space, length of each vector, maximum size AUTOPATH_SDK_KIN_DOFS
Definition: erk_capi_types.h:926
double query_time_secs
required time for collision computation
Definition: erk_capi_types.h:777
const int AUTOPATH_SDK_RESULT_SEED_VALUE
Random starting seed value to influence findpath behavior.
Definition: erk_capi_types.h:881
long JointLimit
Bitmask, specifies which axes reached a joint limit. It is zero if there are no joint limits reached.
Definition: erk_capi_types.h:503
DFRAME m1Tm2
DFRAME transformation from model 1 to model 2
Definition: erk_capi_types.h:778
const long ER_FLYBY_TYPE_UNDEF
Flyby is not active = 0.
Definition: erk_capi_types.h:462
const int AUTOPATH_SDK_AXIS_BIT_22
axisBit Axis 22
Definition: erk_capi_types.h:844
const int INV_WARN_CNFG
ERROR calulating inverse solution for current robot configuration.
Definition: erk_capi_types.h:702
const long ER_LOG_TYPE_MSG
simple Log Message, callback function TerLogProc()
Definition: erk_capi_types.h:279
ER_REAL_TYPE * CartConstraintMin
minimum cartesian constraint value, size ER_DIM
Definition: erk_capi_types.h:935
const long ER_CIRC_ORI_INTERPOLATION_START_VIA_END
Use start-,via- and end-location for orientation interpolation on a circle, erSELECT_CIRCULAR_ORIENTA...
Definition: erk_capi_types.h:419
const long TRK_WND_WAITING
Robot is waiting for Tracking window = 1.
Definition: erk_capi_types.h:490
DFRAME CartPos
initial robot cartesian position w.r.t robot base
Definition: erk_capi_types.h:373
const int AUTOPATH_SDK_AXIS_BIT_12
axisBit Axis 12
Definition: erk_capi_types.h:834
const int AUTOPATH_SDK_AXIS_BIT_19
axisBit Axis 19
Definition: erk_capi_types.h:841
const long ER_CIRC
Motion Type CIRC circular motion using via point, erSELECT_MOTION_TYPE()
Definition: erk_capi_types.h:397
double * GeoSizeParameter
Primitive parameter of loaded geometry and depending on GeoType, maximum length ER_GEO_PARAMETER_MAX.
Definition: erk_capi_types.h:268
double distance
minimum distance>0 if models not colliding, else distance is 0
Definition: erk_capi_types.h:796
UINT Accuracy
[1..100]
Definition: erk_capi_types.h:939
const int AUTOPATH_SDK_AXIS_TYPE_TRACK
Axis Type External Track axis.
Definition: erk_capi_types.h:869
const int ER_COLL_FIRST_CONTACT
report first intersecting tri pair found, erColl_ChkCollision()
Definition: erk_capi_types.h:752
const int AUTOPATH_SDK_STATUS_MP_START
AutoPath calculation started.
Definition: erk_capi_types.h:903
const long KIN_COUNTER_WEIGHT_UNKNOWN
Robot has no information about counter weight.
Definition: erk_capi_types.h:717
const int AUTOPATH_SDK_CHK_CONSTRAINT_COLLISION
action parameter is Collision for callback fct SetCallback_CheckConstraints()
Definition: erk_capi_types.h:892
const int ER_COLL_ERR_UNPROCESSED_MODEL
Returned when an unprocessed model is passed to a function which expects only processed models,...
Definition: erk_capi_types.h:757
const int ER_GEO_ATTRIBUTES_WIRE
GeoAttributes render wire, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:233
void * TErExtraData
additional notification data, tbd, TerNotifyProc()
Definition: erk_capi_types.h:336
const long ER_SYNC_UNDEF
device synchronization not defined
Definition: erk_capi_types.h:355
double SpeedReduce
If speed_reduction is enabled [0.0005..1], erSetSpeedReductionEnable()
Definition: erk_capi_types.h:544
const long ER_EVENT_BOOL_OFF
Event status for binary input/output events is OFF.
Definition: erk_capi_types.h:597
const long ER_NOTIFY_TYPE_MSG
Notify Type Level: OK 0, send simple messages with ER_NOTIFY_DOMAIN_OK or ER_NOTIFY_CODE_OK.
Definition: erk_capi_types.h:284
const int ER_APIDLL_CNTRL_INITIALIZE
Calling status for API-DLL, Initialization allowing to allocate dynamically memory or establish a TCP...
Definition: erk_capi_types.h:114
const long ER_DOF6
6 Degrees-of-Freedom
Definition: erk_capi_types.h:97
double PathLengthRemaining
Remaining path length until target reached.
Definition: erk_capi_types.h:558
const long ER_LS_MAXSTR
Maximum length of a long message.
Definition: erk_capi_types.h:104
const long ER_CSTEP_STATUS_IPO_MOTION_STOPPED
current step status Robot motion was stopped
Definition: erk_capi_types.h:518
const int AUTOPATH_SDK_AXIS_BIT_24
axisBit Axis 24
Definition: erk_capi_types.h:846
const long ER_EVENT_CONDITION_WAIT_DIN_GT
event condition for binary input, wait until DIN is greater than given value
Definition: erk_capi_types.h:607
double * p1
position at model 1 for shortest distance if minimum distance>0
Definition: erk_capi_types.h:797
const int AUTOPATH_SDK_AXIS_BIT_21
axisBit Axis 21
Definition: erk_capi_types.h:843
unsigned int TErTargetID
unique Target identifier
Definition: erk_capi_types.h:198
TErGeoHandle GeoHandle
unique geometry handle created by host application
Definition: erk_capi_types.h:258
const long ER_AUTOACCEL_MODE_AX
4-auto accel calculation joints aq_axis,aq_decel_axis = f(vq_axis), erSetAutoAccel()
Definition: erk_capi_types.h:409
const int ER_GEO_ATTRIBUTES_SHOW_TRANSPARENT
GeoAttributes geometry visualized transparent, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:245
const int AUTOPATH_SDK_AXIS_BIT_2
axisBit Axis 2
Definition: erk_capi_types.h:824
sets the robot model to a position according to the input data. Usage with erSET_INITIAL_POSITION()
Definition: erk_capi_types.h:372
unsigned int * ER_TARGET_EXTAX_DEVICE_CONVEYOR_HND
unique External device definition for Conveyor
Definition: erk_capi_types.h:214
const long ER_ROT_ZYZ
Rotation Index: RotZ*RotY*RotZ, Staeubli CS7, erMath_VecToFrameIdx(), erMath_FrameToVecIdx.
Definition: erk_capi_types.h:732
const int ER_COLL_ERR_MODEL_OUT_OF_MEMORY
Returned when an API function cannot obtain enough memory to store or process a PQP_Model object.
Definition: erk_capi_types.h:755
const long ER_RRRRRR_ID
Device modelled as fixed articulated RRR:RRR type, such as Manutec.
Definition: erk_capi_types.h:362
A pair of two colliding triangles, see erColl_GetResults_Collide()
Definition: erk_capi_types.h:767
const int ER_GEO_ATTRIBUTES_UNDEF
GeoAttributes undefined, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:231
const long TRK_WND_NOT_ACTIVE
Tracking window is not active = 0.
Definition: erk_capi_types.h:489
const long ER_SYNC_CONVEYOR
device synchronization for track motion with Conveyor, tbd
Definition: erk_capi_types.h:358
const int AUTOPATH_SDK_STATUS_MP_DEL_WAYPOINTS
AutoPath delete at least one WayPoint, while minimize number of way points.
Definition: erk_capi_types.h:910
double speed_value
Speed for cartesian motion [m/sec].
Definition: erk_capi_types.h:476
const long ER_AUTOACCEL_MODE_ORI
2-auto accel calculation for orientation ax_ori,axe_ori = f(vx_ori), erSetAutoAccel()
Definition: erk_capi_types.h:408
const int ER_GEO_ATTRIBUTES_COLL_REF_EXCL_PARENT
GeoAttributes geometry object memory model 0-GEO_COLL_REF_EXCL_UNDEF, 1-GEO_COLL_REF_EXCL_PARENT,...
Definition: erk_capi_types.h:248
const long ER_NOTIFY_DOMAIN_GLOBAL
Domain notify level: GLOBAL 1-100.
Definition: erk_capi_types.h:290
const int AUTOPATH_SDK_RESULT_QUALITY_INDEX
Quality Index based on calculated way points.
Definition: erk_capi_types.h:882
const long ER_PTP_TARGET_CALC_MODE_SHORTEST_ANGLE
PTP solution calculated by shortest angle, NEXT_TARGET_DATA.
Definition: erk_capi_types.h:400
const long ER_PTP_TARGET_CALC_MODE_IN_TRAVEL_RANGE
PTP solution calculated within travel ranges, if possible, NEXT_TARGET_DATA.
Definition: erk_capi_types.h:403
unsigned int * ER_TOOLPATH_HND
unique Tool path handle, created with erInitToolPath()
Definition: erk_capi_types.h:202
const int AUTOPATH_SDK_CHK_CONSTRAINT_TBD_400
action parameter is tbd
Definition: erk_capi_types.h:900
const int AUTOPATH_SDK_AXIS_BIT_6
axisBit Axis 6
Definition: erk_capi_types.h:828
const int AUTOPATH_SDK_STATUS_MP_FAILURE
AutoPath calculation failed.
Definition: erk_capi_types.h:906
double value
bool, Duration, DurationMax, OverrideMin, Override
Definition: erk_capi_types.h:351
const int ER_MOP_GNS_TARGET_REACHED
Get Next Step, Need more data, nothing to do.
Definition: erk_capi_types.h:590
const int AUTOPATH_SDK_AXIS_BIT_7
axisBit Axis 7
Definition: erk_capi_types.h:829
const int AUTOPATH_SDK_CHK_CONSTRAINT_SWE
action parameter is SWE exceeded for callback fct SetCallback_CheckConstraints()
Definition: erk_capi_types.h:893
const int AUTOPATH_SDK_CONSTRAINT_RESET
Reset Constraints to min. and max. travel ranges.
Definition: erk_capi_types.h:885
const long ER_CIRC_ORI_INTERPOLATION_TANGENTIAL
Tangential dependent on orientation in start-location for orientation interpolation on a circle,...
Definition: erk_capi_types.h:421
long ax_idx
axis identifier the loaded geometry belongs to. >=0 active joints, <0 passivee joints
Definition: erk_capi_types.h:264
const int AUTOPATH_SDK_CHK_CONSTRAINT_DEST
action parameter is DestPose for callback fct SetCallback_CheckConstraints()
Definition: erk_capi_types.h:891
double PathLengthMoving
moving path length, since motion starts
Definition: erk_capi_types.h:557
const long ER_LIN
Motion Type LIN linear motion, erSELECT_MOTION_TYPE()
Definition: erk_capi_types.h:395
double query_time_secs
required time for collision computation
Definition: erk_capi_types.h:806
const long ER_LOG_TYPE_WARNING
warning Log Message, callback function TerLogProc()
Definition: erk_capi_types.h:280
const int AUTOPATH_SDK_RESULT_SECONDS
Elapsed time in seconds for AutoPath calculation.
Definition: erk_capi_types.h:875
long step_number
counts the number of get next step
Definition: erk_capi_types.h:528
TErTrackingWindowID TrackingWindowID
unique target identifier for Tracking Window
Definition: erk_capi_types.h:540
const int AUTOPATH_SDK_AXIS_TYPE_ROBOT
Axis Type Robot axis.
Definition: erk_capi_types.h:868
long NumberOfEvents
Specifies the number of events, tbd.
Definition: erk_capi_types.h:504
const long ER_NOTIFY_CODE_OK
Code notify level: OK 0.
Definition: erk_capi_types.h:296
const int ER_APIDLL_CNTRL_SIM_START
Calling status for API-DLL, Start indicates that the simulation starts.
Definition: erk_capi_types.h:116
const long ER_AUTOACCEL_MODE_OFF
0 no auto accel calculation, erSetAutoAccel()
Definition: erk_capi_types.h:406
const long ER_LOG_TYPE_CONSOLE
Log Message output to console window.
Definition: erk_capi_types.h:278
INT_PTR * deviceHandle
Unique device handle an axis belongs to, size nConfig.
Definition: erk_capi_types.h:927
const long ER_NOTIFY_CODE_IPO_EXEC_AXIS_ACCEL_EXCEED
Code notify warning, maximum joint acceleration exceeded.
Definition: erk_capi_types.h:323
struct _NEXT_STEP_DATA NEXT_STEP_DATA
DFRAME m1Tm2
DFRAME transformation from model 1 to model 2
Definition: erk_capi_types.h:807
const int ER_APIDLL_CNTRL_UNDEF
Calling status for API-DLL is undefined.
Definition: erk_capi_types.h:113
const int AUTOPATH_SDK_RESULT_COBSTACLE
Number of CObstacle Checks during AutoPath calculation.
Definition: erk_capi_types.h:878
const long TRK_WND_INSIDE
Robot is inside Tracking window = 2;.
Definition: erk_capi_types.h:491
const int INV_WARN_ERROR
ERROR in inverse kinematics calculation.
Definition: erk_capi_types.h:698
long closer_than_tolerance
0- >tolerance, 1- <= tolerance
Definition: erk_capi_types.h:808
const long KIN_COUNTER_WEIGHT_NO
Robot has no counter weight.
Definition: erk_capi_types.h:715
const long ER_EVENT_CONDITION_WAIT_DIN_LE
event condition for binary input, wait until DIN is less or equal given value
Definition: erk_capi_types.h:610
const long JNT_TYPE_ROT
Robot Joint is rotational.
Definition: erk_capi_types.h:683
const long ER_LICENSE_PRIORITY_DEFAULT
check Lmngr license first
Definition: erk_capi_types.h:276
unsigned int * Host_HND
unique Host handle given from Host, NULL per default, erInitKin()
Definition: erk_capi_types.h:196
const long JNT_CHAIN_TYPE_NO_CHAIN
Robot Joint is NOT in the kinematics chain.
Definition: erk_capi_types.h:691
const long ER_ROT_Z9XZ
Rotation Index: RotZ*RotX*RotZ,b+m T1 xx5xx, [-90..+90] [-180..+180] [-180..+180],...
Definition: erk_capi_types.h:740
Group synchronization data structure Used with callback function TerGrpSyncProc()
Definition: erk_capi_types.h:348
const long ER_LICENSE_PRIORITY_UNDEF
license priority not defined
Definition: erk_capi_types.h:273
const long ER_CSTEP_STATUS_VIA_POINT
current step status ViaPoint is set, waiting for CIRC Target
Definition: erk_capi_types.h:515
double LeadWaitTime
Leading time, before move will start.
Definition: erk_capi_types.h:451
const long ER_ROT_XYZ
Rotation Index: RotX*RotY*RotZ, EASY-ROB, Staeubli CS8, erMath_VecToFrameIdx(), erMath_FrameToVecIdx.
Definition: erk_capi_types.h:729
ER_REAL_TYPE * SpeedWeight
]0..1], size nConfig, currently not used
Definition: erk_capi_types.h:937
const long ER_ROT_RPY
Rotation Index: Roll Pitch Yaw, RotX*RotY*RotZ, not relative, Fanuc, Denso, erMath_VecToFrameIdx(),...
Definition: erk_capi_types.h:734
Collision results for query ER_COLL_QUERY_TYPE_DISTANCE, see erColl_GetResults_Distance() The followi...
Definition: erk_capi_types.h:790
const long ER_AUTOACCEL_MODE_ON
all accel calculation enabled, erSetAutoAccel()
Definition: erk_capi_types.h:411
const int AUTOPATH_SDK_AXIS_BIT_18
axisBit Axis 18
Definition: erk_capi_types.h:840
char * FileName
file name geometetry file to be loaded
Definition: erk_capi_types.h:259
const long ER_ROT_Z9XY
Rotation Index: RotZ*RotX*RotY,b+m T1 xx6xx, [-90..+90] [-180..+180] [-180..+180],...
Definition: erk_capi_types.h:739
double PathLength
complete path length of current motion
Definition: erk_capi_types.h:556
const long ER_NOTIFY_TYPE_ERROR
Notify Type Level: ERROR 2.
Definition: erk_capi_types.h:286
const long ER_AUTOACCEL_MODE_POS
1-auto accel calculation for position ax,axe = f(vx), erSetAutoAccel()
Definition: erk_capi_types.h:407
const long JNT_DIRECTION_Z
Robot Joint is in Z direction.
Definition: erk_capi_types.h:688
double DistanceRemaining
Remaining euclidean distance until target reached.
Definition: erk_capi_types.h:562
const long ER_KIN_CONFIGS
Maximum number of possible robot configurations.
Definition: erk_capi_types.h:94
long current_step_status
current step status, as a bitwise inclusive OR operator (|) ER_CSTEP_STATUS_OK, .....
Definition: erk_capi_types.h:526
int id2
identifier triangles 2nd object
Definition: erk_capi_types.h:770
const long ER_GEO_TYPE_IGP
Geometry Type IGP Part file, number of scaling = 3: X-, Y-, Z-scale, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:225
unsigned int * ER_TARGET_INSTRUCTIONS_HND
Instructions, individual information text.
Definition: erk_capi_types.h:205
Geometry data structure for callback function. Used when loading and updating robot geometries With c...
Definition: erk_capi_types.h:257
const long KIN_A2A3_COUPLING_YES
Robot has axis coupling between axis 2 and 3.
Definition: erk_capi_types.h:712
const long ER_ONOFF_ENABLE
enable flag
Definition: erk_capi_types.h:720
unsigned int * ER_COLLISION_HND
unique Collision handle, created with erColl_BeginModel()
Definition: erk_capi_types.h:200
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:651
const long ER_NOTIFY_CODE_IPO_PREP_NOT_POSSIBLE
Code notify, error -78. Cannot prepare motion.
Definition: erk_capi_types.h:311
void * UsrData
User defined data.
Definition: erk_capi_types.h:940
double * p2
position at model 2 for shortest distance if minimum distance>0
Definition: erk_capi_types.h:798
long Configuration
current manipulator configuration [1..
Definition: erk_capi_types.h:538
const long ER_CIRC_ORI_INTERPOLATION_START_VIAORI_END
Use start-,via- and end-location for orientation interpolation on a circle, hereby the robot reaches ...
Definition: erk_capi_types.h:420
double JointAcc[ER_KIN_DOFS]
current joint acceleration [rad/s^2,mm/s^2]
Definition: erk_capi_types.h:534
const long ER_GEO_TYPE_SPHERE
Geometry Type SPHERE, number of parameter = 5: Radius [deg], y-Scale, Angle [deg],...
Definition: erk_capi_types.h:224
const int AUTOPATH_SDK_STATUS_MP_SUCCESS
AutoPath calculation successful.
Definition: erk_capi_types.h:905
const long ER_NOTIFY_DOMAIN_KIN_CALC
Domain notify level: KIN_CALC 201-300.
Definition: erk_capi_types.h:292
const long ER_NOTIFY_CODE_IPO_EXEC_POS_SINGULAR
Code notify warning -1059, Cartesian position is singular.
Definition: erk_capi_types.h:321
double Distance
Euclidean distance between cartesian start and target position.
Definition: erk_capi_types.h:560
const int ER_GEO_ATTRIBUTES_INVISIBLE
GeoAttributes render invisible, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:236
const int AUTOPATH_SDK_CONSTRAINT_MAX
Set ConstraintMax.
Definition: erk_capi_types.h:887
unsigned int * ER_TARGET_MOVE_JOINT_HND
unique Target data for Joint Move handle
Definition: erk_capi_types.h:209
double speed_value
Target speed [m/s,rad/s].
Definition: erk_capi_types.h:432
const int AUTOPATH_SDK_RESULT_CDENSITY
Density in [%] = Number of CObstacle / (Number of CFree + Number of CObstacle) during AutoPath calcul...
Definition: erk_capi_types.h:879
const int AUTOPATH_SDK_CHK_CONSTRAINT_TBD_40
action parameter is tbd
Definition: erk_capi_types.h:896
double JointPosExtAx[ER_EXTAX_KIN_DATA_MAX]
current external axis joint position [rad,mm]
Definition: erk_capi_types.h:537
const int AUTOPATH_SDK_CHK_CONSTRAINT_TBD_20
action parameter is tbd
Definition: erk_capi_types.h:895
Definition: erk_capi_types.h:498
const int ER_MOP_GNTPS_CNTRL_TOOLPATH_OUT
Get Next Tool Path Step, writes contents for current ToolPath into file stream, use with ER_MOP_GNTPS...
Definition: erk_capi_types.h:576
double DistanceMoving
moving euclidean distance, since motion starts
Definition: erk_capi_types.h:561
const int AUTOPATH_SDK_ERROR
Error in AutoPath method.
Definition: erk_capi_types.h:850
const int ER_GEO_ATTRIBUTES_INVERT
GeoAttributes geometry visualized inverted 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:239
long Turns[ER_KIN_DOFS]
current turn values depending on joint position and defined turn interval
Definition: erk_capi_types.h:535
unsigned int TErTrackingWindowID
unique TrackingWindow identifier
Definition: erk_capi_types.h:199
const long ER_ONOFF_STATUS
request current flag status, result ER_ONOFF_DISABLE, ER_ONOFF_ENABLE
Definition: erk_capi_types.h:721
int NotificationDomain
ER_NOTIFY_DOMAIN_OK, ER_NOTIFY_DOMAIN_GLOBAL, ER_NOTIFY_DOMAIN_FILE_IO, ER_NOTIFY_DOMAIN_KIN_CALC,...
Definition: erk_capi_types.h:331
double * GeoAttributeParameter
Attribute parameter of loaded geometry (transparency [0..1], collision tolerance [m]),...
Definition: erk_capi_types.h:270
const long ER_KIN_DOFS
Maximum number of Degrees-of-Freedom for a kinematics.
Definition: erk_capi_types.h:95
const int AUTOPATH_SDK_AXIS_TYPE_EXTERN
Axis Type other external Axis.
Definition: erk_capi_types.h:871
int NotificationCode
Notify code ER_NOTIFY_CODE_WARN_*, ER_NOTIFY_CODE_IPO_*.
Definition: erk_capi_types.h:332
const int ER_MOP_GNTPS_CNTRL_UPDATE_GEO
Get next tool path step, call erUpdateGeo() for each simulation step, use with ER_MOP_GNTPS_CNTRL_NEX...
Definition: erk_capi_types.h:572
const int AUTOPATH_SDK_PARAMETER_SEED_VALUE
Random starting seed value to influence findpath behavior.
Definition: erk_capi_types.h:862
Definition: erk_capi_types.h:471
const long ER_EVENT_CONDITION_WAIT_DIN_GE
event condition for binary input, wait until DIN is greater or equal given value
Definition: erk_capi_types.h:608
long SyncIDDiscCont
relevant SyncID
Definition: erk_capi_types.h:350
const long JNT_CHAIN_TYPE_SEP_NO_CHAIN
Robot Joint is separated & NOT in the kinematics chain.
Definition: erk_capi_types.h:692
const int AUTOPATH_SDK_CHK_CONSTRAINT_CART_SPACE
action parameter is cart space exceeded for callback fct SetCallback_CheckConstraints()
Definition: erk_capi_types.h:894
const long ER_NOTIFY_CODE_IPO_EXEC_RUNNING
Code notify, execution running, internal error -79, Not ready to receive targets.
Definition: erk_capi_types.h:306
Notify data structure Used with callback function TerNotifyProc()
Definition: erk_capi_types.h:329
const int AUTOPATH_SDK_CONSTRAINT_MIN
Set ConstraintMin.
Definition: erk_capi_types.h:886
double JointPos[ER_KIN_DOFS]
Joint position.
Definition: erk_capi_types.h:500
const int AUTOPATH_SDK_AXIS_BIT_1
axisBit Axis 1
Definition: erk_capi_types.h:823
const int AUTOPATH_SDK_AXIS_TRANS
Axis is translational.
Definition: erk_capi_types.h:917
const long ER_GEO_TYPE_CONE
Geometry Type CONE, number of parameter = 6: Radius [deg], Height [m], y-Scale, dx [m],...
Definition: erk_capi_types.h:223
const long ER_COLL_QUERY_TYPE_UNDEF
no collision check
Definition: erk_capi_types.h:746
unsigned int * ER_TARGET_HEAD_HND
unique Header data handle
Definition: erk_capi_types.h:204
const long ER_DOF12
12 Degrees-of-Freedom
Definition: erk_capi_types.h:100
const long ER_NOTIFY_CODE_IPO_POS_OUT_OF_BOUNDARY
Code notify error -1053, Cartesian position is out of boudary work range.
Definition: erk_capi_types.h:319
long RGBColor
color value of loaded geometry
Definition: erk_capi_types.h:261
const long ER_ROT_ZYX
Rotation Index: RotZ*RotY*RotX, KUKA, Reis, Kobelco, erMath_VecToFrameIdx(), erMath_FrameToVecIdx.
Definition: erk_capi_types.h:730
const long ER_DIM
3 Dimensions
Definition: erk_capi_types.h:101
const long ER_EVENT_CONDITION_WAIT_DIN_UNSET
event condition for binary input, wait until DIN is ER_EVENT_BOOL_OFF
Definition: erk_capi_types.h:606
const long ER_SYNC_VR_OFF
device synchronization, tbd
Definition: erk_capi_types.h:359
long SyncIDContinuous
Handle for MotionSync.
Definition: erk_capi_types.h:454
const long ER_SPEED_REDUCTION_ENABLE
Speed reduction is enabled.
Definition: erk_capi_types.h:390
const long ER_OUPUT_FORMAT_CART_JOINT_ANGLE_DIST
desired output_format for erGET_NEXT_STEP is Cartesian and joint angle/distance
Definition: erk_capi_types.h:385
Definition: erk_capi_types.h:919
const long ER_COLL_QUERY_TYPE_TOLERANCE
checks if distance between PQP_Models is <= tolerance, erColl_ChkCollision()
Definition: erk_capi_types.h:749
const int AUTOPATH_SDK_CHK_CONSTRAINT_TBD_800
action parameter is tbd
Definition: erk_capi_types.h:901
const int ER_GEO_ATTRIBUTES_BFACE_CULLING
GeoAttributes geometry visualized back face culling, 0- OFF, 1- ON, see LOAD_GEOMETRY_DATA.
Definition: erk_capi_types.h:240
double axis_value
Target value [m,rad].
Definition: erk_capi_types.h:431
ER_HND er_hnd_connect
Handle of connected device.
Definition: erk_capi_types.h:429
double JointPos[ER_KIN_DOFS]
Target joint position for joint motion and target type ER_TARGET_TYPE_ABSJOINT.
Definition: erk_capi_types.h:486
const int ER_COLL_ERR_BUILD_OUT_OF_SEQUENCE
Returned when: 1. erColl_AddTri() is called before erColl_BeginModel(). 2. erColl_BeginModel() is cal...
Definition: erk_capi_types.h:758
const long ER_DOMINANT_INTERPOLATION_AXIS
3-dominant interpolation type, Axis is master, erSELECT_DOMINANT_INTERPOLATION()
Definition: erk_capi_types.h:415
long MotionType
Motion Type ER_JOINT = ER_PTP = 1, ER_LIN = 2, ER_SLEW = 3, ER_CIRC = 4.
Definition: erk_capi_types.h:541
const double ER_PI
PI.
Definition: erk_capi_types.h:107
TErTargetID TargetID
Identifier of the target, 0 no identifier givin, >0 identifier of this target.
Definition: erk_capi_types.h:473
int * AxisPriority
[1..50..100], size nConfig
Definition: erk_capi_types.h:930
const long ER_EVENT_CONDITION_WAIT_DIN_SET
event condition for binary input, wait until DIN is ER_EVENT_BOOL_ON
Definition: erk_capi_types.h:605
long TargetPosSet
0x0 - not set, 0x1 - CartPos, 0x2 - CartPosVia, 0x4 - JointPos
Definition: erk_capi_types.h:483
const long ER_ROT_Z
Rotation Index: Rotation about z axis, erMath_Frame_Rot()
Definition: erk_capi_types.h:727
double JointVel[ER_KIN_DOFS]
current joint speed [rad/s,mm/s]
Definition: erk_capi_types.h:533
const int ER_APIDLL_CNTRL_TERMINATE
Calling status for API-DLL, Terminate, allowing to delete allocated memory or to terminate a TCP/IP c...
Definition: erk_capi_types.h:115
double joint_speed_percent
Joint speed percentage [1%..200%] for joint motion.
Definition: erk_capi_types.h:478
double TrajectoryTime
resulted trajectory time
Definition: erk_capi_types.h:506
const long ER_LICENSE_PRIORITY_LMNGR
check Lmngr license first
Definition: erk_capi_types.h:274
const long ER_ROT_Z9YX
Rotation Index: RotZ*RotY*RotX,b+m T1 xx4xx, [-90..+90] [-180..+180] [-180..+180] (~KUKA),...
Definition: erk_capi_types.h:741
const int INV_WARN_SWE_EXCEED
Warning: inverse kinematics calculation successful, target location is reachable, but travel ranges a...
Definition: erk_capi_types.h:704
unsigned int * ER_TARGET_MOTION_EXEC_HND
unique handle for motion execution data at target
Definition: erk_capi_types.h:211
TErTargetID TargetID
unique target identifier
Definition: erk_capi_types.h:539
const long ER_GRPSYNC_GET_OV_SPEED_RED_MIN
MoveSync, get min ov of all robots in KIR group.
Definition: erk_capi_types.h:341
const int ER_COLL_ERR_OUT_OF_MEMORY
Returned when a PQP query cannot allocate enough storage to compute or hold query information....
Definition: erk_capi_types.h:756
double flyby_value
Flyby or zone value, depending on flyby type as percentage value [0%..100%], or distance [mm].
Definition: erk_capi_types.h:481
double tolerance
givin tolerance value
Definition: erk_capi_types.h:809
long num_pairs_alloced
current number of allocated pairs
Definition: erk_capi_types.h:779
const long ER_NOTIFY_CODE_IPO_NEW_PREP_PATH
Code notify, preparation running,internal error -79, Not ready to receive targets.
Definition: erk_capi_types.h:307
const int ER_GEO_ATTRIBUTES_DEFAULT
GeoAttributes default settings.
Definition: erk_capi_types.h:250
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:662
const int ER_COLL_ALL_CONTACTS
find all pairwise intersecting triangles, erColl_ChkCollision()
Definition: erk_capi_types.h:751
const long ER_CSTEP_STATUS_INV_WARNING
current step status Inverse Kinematics with warnings
Definition: erk_capi_types.h:519
const int AUTOPATH_SDK_AXIS_BIT_5
axisBit Axis 5
Definition: erk_capi_types.h:827
DFRAME CartPos
current cartesian TCP position w.r.t. Work Object
Definition: erk_capi_types.h:529
const double AUTOPATH_SDK_KIN_EPSI
epsi
Definition: erk_capi_types.h:819
const long ER_NOTIFY_TYPE_WARNING
Notify Type Level: Warning 1.
Definition: erk_capi_types.h:285
const long ER_ROT_CA
Rotation Index: Tricept C-RotZ, A-RotX, NC, erMath_VecToFrameIdx(), erMath_FrameToVecIdx.
Definition: erk_capi_types.h:736
const int AUTOPATH_SDK_RESULT_CHECKS
Number of Checks during AutoPath calculation.
Definition: erk_capi_types.h:874
Definition: erk_capi_types.h:428
const long ER_LOG_TYPE_STATUS
status Log Message, callback function TerLogProc()
Definition: erk_capi_types.h:282
const long ER_SYNC_OFF
device synchronization OFF
Definition: erk_capi_types.h:356
const double ER_mm2m
Conversion from [m] to [mm].
Definition: erk_capi_types.h:110
const long ER_PTP_TARGET_CALC_MODE_VAR_CONFIG
PTP solution calculated by variable configuration, NEXT_TARGET_DATA.
Definition: erk_capi_types.h:404
const long ER_NOTIFY_CODE_IPO_EXEC_ERROR
Code notify internal error -68, stop Get_Next_Step.
Definition: erk_capi_types.h:317
const int AUTOPATH_SDK_PARAMETER_NTREES
Number of Trees [2..32].
Definition: erk_capi_types.h:856
const long ER_AUTOACCEL_MODE_DEF
Default: auto accel calculation for position and orientation, erSetAutoAccel()
Definition: erk_capi_types.h:410
unsigned int * ER_TARGET_ATTRIBUTES_AUX_HND
unique Auxiliary motion attributes handle
Definition: erk_capi_types.h:207
double TrajectoryTimeMoving
current moving time, since motion starts
Definition: erk_capi_types.h:552
const int ER_MOP_SNT_ERROR
Set Next Target, Error.
Definition: erk_capi_types.h:583
const long ER_ROT_Y
Rotation Index: Rotation about y axis, erMath_Frame_Rot()
Definition: erk_capi_types.h:726