EASY-ROB™ Application Programming Interface  v9.301
Static Public Member Functions | List of all members
ER_CAPI_TARGETS_TAG Class Reference

Method class for manipulation of tags and access tag attributes. More...

#include <ER_CAPI.H>

Inheritance diagram for ER_CAPI_TARGETS_TAG:
ER_CAPI_TARGETS ER_CAPI

Static Public Member Functions

static ER_DllExport int chk_rob_tag_idx (int idx)
 Check if tag index is valid. More...
 
static ER_DllExport frameinq_rob_tag_T_cRBase_idx (int idx)
 Temporary Tcp location w.r.t to cRobot Base
This Tcp location w.r.t to cRobot Base is saved when the cRobot reaches this Tag
See inq_rob_tag_q_cR_idx() , inq_rob_tag_uid_cR_idx() More...
 
static ER_DllExport float * inq_rob_tag_q_cR_idx (int idx)
 Temporary joint location for cRobot
This Joint location is saved when the cRobot reaches this Tag
See inq_rob_tag_T_cRBase_idx() , inq_rob_tag_uid_cR_idx() More...
 
static ER_DllExport ER_UID * inq_rob_tag_uid_cR_idx (int idx)
 Temporary unique robot id of cRobot
This Unique robot ID of the cRobot is saved when the cRobot reaches this Tag
See inq_rob_tag_T_cRBase_idx() , inq_rob_tag_q_cR_idx() More...
 
static ER_DllExport char * inq_rob_tag_prefix_idx (int idx)
 Tag_attributes, get tag prefix
The complete tag name is tagprefix + tagname
See inq_rob_tag_name_idx(), inq_rob_tag_prefix_name_idx() More...
 
static ER_DllExport char * inq_rob_tag_name_idx (int idx)
 Tag_attributes, get tag name (=postfix)
The complete tag name is tagprefix + tagname
See inq_rob_tag_prefix_idx(), inq_rob_tag_prefix_name_idx() More...
 
static ER_DllExport char * inq_rob_tag_prefix_name_idx (int idx)
 Tag_attributes, complete tag name
The complete tag name is tagprefix + tagname See inq_rob_tag_prefix_idx() , inq_rob_tag_name_idx() More...
 
static ER_DllExport int * inq_rob_tag_motype_idx (int idx)
 Tag_attributes, motion type. More...
 
static ER_DllExport float * inq_rob_tag_speed_ptp_idx (int idx)
 Tag_attributes, ptp speed, 0-def, [rad/s]
Remarks
use inq_rob_tag_speed_ptp_ov_idx() instead. More...
 
static ER_DllExport float * inq_rob_tag_speed_cp_idx (int idx)
 Tag_attributes, cp speed, 0-def, [m/s]
. More...
 
static ER_DllExport float * inq_rob_tag_speed_ori_idx (int idx)
 Tag_attributes, ori speed, 0-def, [rad/s]. More...
 
static ER_DllExport int * inq_rob_tag_confdata_idx (int idx)
 Tag_attributes, robot configuration, 0-def. More...
 
static ER_DllExport float * inq_rob_tag_zone_idx (int idx)
 Tag_attributes, programmed zone value [mm,%]. More...
 
static ER_DllExport float * inq_rob_tag_accel_ptp_idx (int idx)
 Tag_attributes, ptp acceleration, 0-def, [rad/s^2]
Remarks
use inq_rob_tag_accel_ptp_ov_idx() instead. More...
 
static ER_DllExport float * inq_rob_tag_accel_cp_idx (int idx)
 Tag_attributes, cp acceleration, 0-def, [m/s^2]. More...
 
static ER_DllExport float * inq_rob_tag_accel_ori_idx (int idx)
 Tag_attributes, orientation acceleration, 0-def, [rad/s^2]. More...
 
static ER_DllExport float * inq_rob_tag_ov_pro_idx (int idx)
 Tag_attributes, programmed override, 0-def [0-200%]. More...
 
static ER_DllExport float * inq_rob_tag_speed_ptp_ov_idx (int idx)
 Tag_attributes, ptp override speed, 0-def [0-200%]. More...
 
static ER_DllExport float * inq_rob_tag_speed_cp_ov_idx (int idx)
 Tag_attributes, cp override speed, 0-def [0-200%]. More...
 
static ER_DllExport float * inq_rob_tag_speed_ori_ov_idx (int idx)
 Tag_attributes, ori override speed, 0-def [0-200%]. More...
 
static ER_DllExport float * inq_rob_tag_accel_ptp_ov_idx (int idx)
 Tag_attributes, ptp override accel, 0-def [0-200%]. More...
 
static ER_DllExport float * inq_rob_tag_accel_cp_ov_idx (int idx)
 Tag_attributes, cp override accel, 0-def [0-200%]. More...
 
static ER_DllExport float * inq_rob_tag_accel_ori_ov_idx (int idx)
 Tag_attributes, ori override accel, 0-def [0-200%]. More...
 
static ER_DllExport int * inq_rob_tag_auto_accel_idx (int idx)
 Tag_attributes, auto acceleration, 0-def
If auto accel is enabled for a tag, the accelerations for ptp and cp mmoves are calculated automatically depending on programmed speed. More...
 
static ER_DllExport float * inq_rob_tag_acc_set_acc_idx (int idx)
 Tag_attributes, AccSet Acc, 100-def [20-100%]
Set AccSet Acc to 20% for smooth acceleration
Set AccSet Acc to 100% for max. acceleration
See inq_rob_tag_acc_set_ramp_idx() More...
 
static ER_DllExport float * inq_rob_tag_acc_set_ramp_idx (int idx)
 Tag_attributes, AccSet Ramp, 100-def [20-100%]
Set AccSet Ramp to 20% for smooth acceleration
Set AccSet Ramp to 100% for max. acceleration
See inq_rob_tag_acc_set_acc_idx() More...
 
static ER_DllExport int * inq_rob_tag_no_decel_idx (int idx)
 Tag_attributes, No decelaration at target
If deceleration flag is 0, the motion decelerates at the target, this is default
If deceleration flag is 1, the motion will not decelerate at the target. More...
 
static ER_DllExport int * inq_rob_tag_leading_pos_idx (int idx)
 tag_attributes, Leading behavior for CP motion
2 - VAR the slowest is dominant, default
1 - Pos the position is dominant
0 - Ori the orientation is dominant More...
 
static ER_DllExport float * inq_rob_tag_lead_time_idx (int idx)
 tag_attributes, wait time before move begins, 0-def [s] More...
 
static ER_DllExport float * inq_rob_tag_lag_time_idx (int idx)
 tag_attributes, wait time when targte reached, 0-def [s] More...
 
static ER_DllExport int * inq_rob_tag_lin_ori_mode_idx (int idx)
 tag_attributes, orientation interpolation mode for LIN motion type
default is 4 - LIN_QUATERNION More...
 
static ER_DllExport int * inq_rob_tag_circ_ori_mode_idx (int idx)
 tag_attributes, orientation interpolation mode for CIRC motion type
default is 5 - CIRC_QUATERNION More...
 
static ER_DllExport float * inq_rob_tag_speed_ptp_ax_ov_idx (int idx)
 tag_attributes, ptp_ax override speed 0-def [0-200%] More...
 
static ER_DllExport float * inq_rob_tag_accel_ptp_ax_ov_idx (int idx)
 tag_attributes, ptp_ax override accel 0-def [0-200%] More...
 
static ER_DllExport int * inq_rob_tag_turn_use_idx (int idx)
 tag_attributes, turn flag, 0-do not use turn values (def), 1-use turns
If use turns is anabled, defined turn attributes are considered
see inq_rob_tag_turn_ax_idx() More...
 
static ER_DllExport int * inq_rob_tag_turn_ax_idx (int idx)
 tag_attributes, turn values depending on current robots turn interval
see inq_rob_tag_turn_use_idx() More...
 
static ER_DllExport char * inq_rob_tag_user_string_idx (int idx)
 tag_attributes, user defined Tag string
To store miscellaneous user data More...
 
static ER_DllExport int * inq_rob_tag_color_idx (int idx)
 tag_attributes, color of tag
Use inq_rob_tag_color_set_idx() to change the color More...
 
static ER_DllExport int inq_rob_tag_color_set_idx (int idx, int color)
 tag_attributes, set color of tag
More...
 
static ER_DllExport float * inq_rob_tag_length_idx (int idx)
 tag_attributes, tag length [m]
Tag size for visualization More...
 
static ER_DllExport int * inq_rob_tag_render_idx (int idx)
 tag_attributes, tag render
Tag render is one of COORSYS_RENDER_STYLE_COORSYS_XYZ=0, COORSYS_RENDER_STYLE_APPROACH_Zx=1, COORSYS_RENDER_STYLE_APPROACH_Xy=2, COORSYS_RENDER_STYLE_APPROACH_Yz=3, COORSYS_RENDER_STYLE_POINT=4, COORSYS_RENDER_STYLE_INVISIBLE=5 More...
 
static ER_DllExport int * inq_rob_tag_z_buffering_idx (int idx)
 tag_attributes, tag z_buffering
Tag z_buffering is one of COORSYS_Z_BUFFERING_OFF, COORSYS_Z_BUFFERING_ON More...
 
static ER_DllExport frameinq_rob_tag_frame_idx (int idx)
 tag_attributes, tag location w.r.t. it work object frame
see More...
 
static ER_DllExport frameinq_rob_tag_frame_strt_idx (int idx)
 tag_attributes, tag start location w.r.t. it work object frame
A tag start location is the start condition, a tag has when a path or cell is loaded More...
 
static ER_DllExport int * inq_rob_tag_n_extax_idx (int idx)
 tag_attributes number of external axis More...
 
static ER_DllExport float * inq_rob_tag_extax_idx (int idx)
 tag_attributes external axis value []
See inq_rob_tag_n_extax_idx(), inq_rob_tag_extaxjnt_idx(), inq_rob_tag_extaxtype_idx() More...
 
static ER_DllExport int * inq_rob_tag_extaxjnt_idx (int idx)
 tag_attributes, idx of controlled axis []
Contains the idx of the controlled joint of the cRobot
See inq_rob_tag_n_extax_idx(), inq_rob_tag_extax_idx(), inq_rob_tag_extaxtype_idx(), More...
 
static ER_DllExport char * inq_rob_tag_extaxtype_idx (int idx)
 tag_attributes, type 'R' or 'T' of controlled joint []
Contains the type of the controlled joint of the cRobot
See inq_rob_tag_n_extax_idx(), inq_rob_tag_extax_idx(), inq_rob_tag_extaxjnt_idx() More...
 
static ER_DllExport int delete_cTag ()
 Deletes cTag
see also ER_CAPI_SYS_STATUS::UnloadTag() More...
 
static ER_DllExport int inq_Get_c_tag_idx ()
 Get current tag idx [1..n_tags] in current path. More...
 
static ER_DllExport int inq_Set_tag_idx (int tag_idx)
 Set current tag idx [1..n_tags] in current path. More...
 
static ER_DllExport char * inq_Get_c_tag_name ()
 Get current tag name = prefix + postfix. More...
 
static ER_DllExport frameinq_Get_c_tag_frame ()
 Get current tag location w.r.t. wobj frame location. More...
 
static ER_DllExport frameinq_Get_c_tag_frame_strt ()
 Get current start tag location w.r.t. wobj frame location. More...
 
static ER_DllExport int swap_TagUp (void)
 Swaps Tag pointer with the prev Tag. More...
 
static ER_DllExport int swap_TagDown (void)
 Swaps Tag pointer with the next Tag
. More...
 
static ER_DllExport int copy_current_tag_data (void)
 Copies cTag to tag_copy and to show tag 'c_tag'
This method copies all cTag data to the "copyTag"
The contend of the "copyTag" is used when creating new Tags. More...
 
static ER_DllExport int NewTagOnTcp (void)
 Creates a new Tag in current path at Tcp of cRobot. More...
 
static ER_DllExport int cTagClone (int create_new=0)
 Clones current Tag in current path or creates new one at Tcp of cRobot
If parameter create_new is 0, the cTag will be cloned.
If parameter create_new is 1, a new Tag will be created at the robots tcp.
Mote: If cPath is empty, a new tag will be created on TCP if create_new is 1. More...
 
static ER_DllExport int Shift_cTagOnTcp (void)
 Shifts cTag to the Tcp of cRobot
The cTag will jump to the cRobot Tcp. More...
 
static ER_DllExport int NewTagOnFrame (frame *T)
 Creates a new Tag in current path at location of frame 'T',
without grf_update and TagDlg update. More...
 
static ER_DllExport int NewTagOnFrame_update (frame *T, int update_mode)
 Creates a new Tag in current path at location of frame 'T'
Parameter is a bitwise inclusive OR operator (|) of. More...
 
static ER_DllExport int Shift_cTagOnFrame (frame *T)
 Shifts cTag to location of frame 'T'. More...
 
static ER_DllExport int NewTagOnPickPoint (int vertices=0)
 Creates a new Tag at current picked location
If vertices = 1 : keep cOrientation
If vertices = 0 : use polygon normal for approach direction. More...
 
static ER_DllExport int Shift_cTagOnPickPoint (int vertices=0)
 Shifts cTag to the current picked location
If vertices = 1 : keep cOrientation
If vertices = 0 : use polygon normal for approach direction. More...
 
static ER_DllExport void TagClone (void)
 Multiple clone of current Tag
Clone all selected Tags. More...
 

Additional Inherited Members

- Static Public Attributes inherited from ER_CAPI_TARGETS
static ER_CAPI_TARGETS_TAG er_capi_targets_tag
 Method class for manipulation of tags and access tag attributes. More...
 
static ER_CAPI_TARGETS_PATH er_capi_targets_path
 Method class for creating, deleting and manipulating paths. More...
 
- Static Public Attributes inherited from ER_CAPI
static ER_CAPI_USER_IO er_capi_user_io
 Method class for interaction with EASY-ROB. More...
 
static ER_CAPI_DEVICES er_capi_devices
 Method class to create, attach, update devices, for kinematics calculations and for trajectory planning and -execution. More...
 
static ER_CAPI_SIM er_capi_sim
 Method class for simulation settings. More...
 
static ER_CAPI_TARGETS er_capi_targets
 Method class for paths and tags. More...
 
static ER_CAPI_CAD er_capi_cad
 Method class for for 3D CAD Data import and -export, changing attributes and positions. More...
 
static ER_CAPI_SYS er_capi_sys
 Method class for mathematical calculations, simulation status, units. More...
 

Detailed Description

Method class for manipulation of tags and access tag attributes.

Member Function Documentation

◆ chk_rob_tag_idx()

static ER_DllExport int ER_CAPI_TARGETS_TAG::chk_rob_tag_idx ( int  idx)
static

Check if tag index is valid.

Parameters
[in]idxTag index, first tag has idx = 1
Return values
0- OK
1- tag_idx does not exist

◆ copy_current_tag_data()

static ER_DllExport int ER_CAPI_TARGETS_TAG::copy_current_tag_data ( void  )
static

Copies cTag to tag_copy and to show tag 'c_tag'
This method copies all cTag data to the "copyTag"
The contend of the "copyTag" is used when creating new Tags.

Return values
0- OK
1- cannot copy

◆ cTagClone()

static ER_DllExport int ER_CAPI_TARGETS_TAG::cTagClone ( int  create_new = 0)
static

Clones current Tag in current path or creates new one at Tcp of cRobot
If parameter create_new is 0, the cTag will be cloned.
If parameter create_new is 1, a new Tag will be created at the robots tcp.
Mote: If cPath is empty, a new tag will be created on TCP if create_new is 1.

Parameters
[in]create_new
Return values
0- OK
1- cannot clone tag

◆ delete_cTag()

static ER_DllExport int ER_CAPI_TARGETS_TAG::delete_cTag ( )
static

Deletes cTag
see also ER_CAPI_SYS_STATUS::UnloadTag()

Return values
0- OK
1- cannot delete Tag

◆ inq_Get_c_tag_frame()

static ER_DllExport frame* ER_CAPI_TARGETS_TAG::inq_Get_c_tag_frame ( )
static

Get current tag location w.r.t. wobj frame location.

Return values
pointerto FRAME

◆ inq_Get_c_tag_frame_strt()

static ER_DllExport frame* ER_CAPI_TARGETS_TAG::inq_Get_c_tag_frame_strt ( )
static

Get current start tag location w.r.t. wobj frame location.

Return values
pointerto FRAME

◆ inq_Get_c_tag_idx()

static ER_DllExport int ER_CAPI_TARGETS_TAG::inq_Get_c_tag_idx ( )
static

Get current tag idx [1..n_tags] in current path.

Return values
currenttag index

◆ inq_Get_c_tag_name()

static ER_DllExport char* ER_CAPI_TARGETS_TAG::inq_Get_c_tag_name ( )
static

Get current tag name = prefix + postfix.

Return values
completetag name

◆ inq_rob_tag_acc_set_acc_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_acc_set_acc_idx ( int  idx)
static

Tag_attributes, AccSet Acc, 100-def [20-100%]
Set AccSet Acc to 20% for smooth acceleration
Set AccSet Acc to 100% for max. acceleration
See inq_rob_tag_acc_set_ramp_idx()

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto AccSet Acc

◆ inq_rob_tag_acc_set_ramp_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_acc_set_ramp_idx ( int  idx)
static

Tag_attributes, AccSet Ramp, 100-def [20-100%]
Set AccSet Ramp to 20% for smooth acceleration
Set AccSet Ramp to 100% for max. acceleration
See inq_rob_tag_acc_set_acc_idx()

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto AccSet Ramp

◆ inq_rob_tag_accel_cp_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_accel_cp_idx ( int  idx)
static

Tag_attributes, cp acceleration, 0-def, [m/s^2].

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto accel cp value [m/s^2]

◆ inq_rob_tag_accel_cp_ov_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_accel_cp_ov_idx ( int  idx)
static

Tag_attributes, cp override accel, 0-def [0-200%].

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto cp override accel

◆ inq_rob_tag_accel_ori_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_accel_ori_idx ( int  idx)
static

Tag_attributes, orientation acceleration, 0-def, [rad/s^2].

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto accel ori value [rad/s^2]

◆ inq_rob_tag_accel_ori_ov_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_accel_ori_ov_idx ( int  idx)
static

Tag_attributes, ori override accel, 0-def [0-200%].

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto ori override accel

◆ inq_rob_tag_accel_ptp_ax_ov_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_accel_ptp_ax_ov_idx ( int  idx)
static

tag_attributes, ptp_ax override accel 0-def [0-200%]

Parameters
[in]idxTag index, first tag has idx = 1
Return values
ptp_axoverride accel

◆ inq_rob_tag_accel_ptp_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_accel_ptp_idx ( int  idx)
static

Tag_attributes, ptp acceleration, 0-def, [rad/s^2]
Remarks
use inq_rob_tag_accel_ptp_ov_idx() instead.

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto tag accel_ptp value [rad/s^2]

◆ inq_rob_tag_accel_ptp_ov_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_accel_ptp_ov_idx ( int  idx)
static

Tag_attributes, ptp override accel, 0-def [0-200%].

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto ptp override accel

◆ inq_rob_tag_auto_accel_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_auto_accel_idx ( int  idx)
static

Tag_attributes, auto acceleration, 0-def
If auto accel is enabled for a tag, the accelerations for ptp and cp mmoves are calculated automatically depending on programmed speed.

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto auto acceleration

◆ inq_rob_tag_circ_ori_mode_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_circ_ori_mode_idx ( int  idx)
static

tag_attributes, orientation interpolation mode for CIRC motion type
default is 5 - CIRC_QUATERNION

Parameters
[in]idxTag index, first tag has idx = 1
Return values
0- CIRC_VARIABLE
1- CIRC_FIX
2- CIRC_TANGENTIAL
3- CIRC_AUX
4- CIRC_VARIABLE2
5- CIRC_QUATERNION

◆ inq_rob_tag_color_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_color_idx ( int  idx)
static

tag_attributes, color of tag
Use inq_rob_tag_color_set_idx() to change the color

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto tag color

◆ inq_rob_tag_color_set_idx()

static ER_DllExport int ER_CAPI_TARGETS_TAG::inq_rob_tag_color_set_idx ( int  idx,
int  color 
)
static

tag_attributes, set color of tag

int n_tags = er_targets_path.inq_Get_n_tags(); // get number of Tags in cPath
for (int i=1;i<=n_tags;i++)
{
int *color = er_targets_tag.inq_rob_tag_color_idx(i); // get tag color address
}
Parameters
[in]idxTag index, first tag has idx = 1
[in]colorNew tag color
Return values
0- OK
1- Error

◆ inq_rob_tag_confdata_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_confdata_idx ( int  idx)
static

Tag_attributes, robot configuration, 0-def.

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto robot configuration

◆ inq_rob_tag_extax_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_extax_idx ( int  idx)
static

tag_attributes external axis value []
See inq_rob_tag_n_extax_idx(), inq_rob_tag_extaxjnt_idx(), inq_rob_tag_extaxtype_idx()

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto external axis data, maximum size is inq_rob_tag_n_extax_idx()

◆ inq_rob_tag_extaxjnt_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_extaxjnt_idx ( int  idx)
static

tag_attributes, idx of controlled axis []
Contains the idx of the controlled joint of the cRobot
See inq_rob_tag_n_extax_idx(), inq_rob_tag_extax_idx(), inq_rob_tag_extaxtype_idx(),

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto external joint idx, maximum size is inq_rob_tag_n_extax_idx()

◆ inq_rob_tag_extaxtype_idx()

static ER_DllExport char* ER_CAPI_TARGETS_TAG::inq_rob_tag_extaxtype_idx ( int  idx)
static

tag_attributes, type 'R' or 'T' of controlled joint []
Contains the type of the controlled joint of the cRobot
See inq_rob_tag_n_extax_idx(), inq_rob_tag_extax_idx(), inq_rob_tag_extaxjnt_idx()

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto type string, maximum string length inq_rob_tag_n_extax_idx()

◆ inq_rob_tag_frame_idx()

static ER_DllExport frame* ER_CAPI_TARGETS_TAG::inq_rob_tag_frame_idx ( int  idx)
static

tag_attributes, tag location w.r.t. it work object frame
see

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto FRAME

◆ inq_rob_tag_frame_strt_idx()

static ER_DllExport frame* ER_CAPI_TARGETS_TAG::inq_rob_tag_frame_strt_idx ( int  idx)
static

tag_attributes, tag start location w.r.t. it work object frame
A tag start location is the start condition, a tag has when a path or cell is loaded

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto FRAME

◆ inq_rob_tag_lag_time_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_lag_time_idx ( int  idx)
static

tag_attributes, wait time when targte reached, 0-def [s]

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto lag time

◆ inq_rob_tag_lead_time_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_lead_time_idx ( int  idx)
static

tag_attributes, wait time before move begins, 0-def [s]

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto lead time

◆ inq_rob_tag_leading_pos_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_leading_pos_idx ( int  idx)
static

tag_attributes, Leading behavior for CP motion
2 - VAR the slowest is dominant, default
1 - Pos the position is dominant
0 - Ori the orientation is dominant

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto Leading behavior

◆ inq_rob_tag_length_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_length_idx ( int  idx)
static

tag_attributes, tag length [m]
Tag size for visualization

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto tag length

◆ inq_rob_tag_lin_ori_mode_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_lin_ori_mode_idx ( int  idx)
static

tag_attributes, orientation interpolation mode for LIN motion type
default is 4 - LIN_QUATERNION

Parameters
[in]idxTag index, first tag has idx = 1
Return values
0- LIN_VARIABLE
1- LIN_FIX
2- LIN_TANGENTIAL
3- LIN_AUX
4- LIN_QUATERNION

◆ inq_rob_tag_motype_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_motype_idx ( int  idx)
static

Tag_attributes, motion type.

Parameters
[in]idxTag index, first tag has idx = 1
Return values
0- TAG_MOTYPE_DEF
1- TAG_MOTYPE_PTP
2- TAG_MOTYPE_LIN
3- TAG_MOTYPE_CIRC
4- TAG_MOTYPE_VIA
5- TAG_MOTYPE_SLEW

◆ inq_rob_tag_n_extax_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_n_extax_idx ( int  idx)
static

tag_attributes number of external axis

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto number of external axis

◆ inq_rob_tag_name_idx()

static ER_DllExport char* ER_CAPI_TARGETS_TAG::inq_rob_tag_name_idx ( int  idx)
static

Tag_attributes, get tag name (=postfix)
The complete tag name is tagprefix + tagname
See inq_rob_tag_prefix_idx(), inq_rob_tag_prefix_name_idx()

Parameters
[in]idxTag index, first tag has idx = 1
Return values
tagname

◆ inq_rob_tag_no_decel_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_no_decel_idx ( int  idx)
static

Tag_attributes, No decelaration at target
If deceleration flag is 0, the motion decelerates at the target, this is default
If deceleration flag is 1, the motion will not decelerate at the target.

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto no deceleration flag

◆ inq_rob_tag_ov_pro_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_ov_pro_idx ( int  idx)
static

Tag_attributes, programmed override, 0-def [0-200%].

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto programmed override, 0-def [0-200%]

◆ inq_rob_tag_prefix_idx()

static ER_DllExport char* ER_CAPI_TARGETS_TAG::inq_rob_tag_prefix_idx ( int  idx)
static

Tag_attributes, get tag prefix
The complete tag name is tagprefix + tagname
See inq_rob_tag_name_idx(), inq_rob_tag_prefix_name_idx()

Parameters
[in]idxTag index, first tag has idx = 1
Return values
tagprefix

◆ inq_rob_tag_prefix_name_idx()

static ER_DllExport char* ER_CAPI_TARGETS_TAG::inq_rob_tag_prefix_name_idx ( int  idx)
static

Tag_attributes, complete tag name
The complete tag name is tagprefix + tagname See inq_rob_tag_prefix_idx() , inq_rob_tag_name_idx()

Parameters
[in]idxTag index, first tag has idx = 1
Return values
completetag name

◆ inq_rob_tag_q_cR_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_q_cR_idx ( int  idx)
static

Temporary joint location for cRobot
This Joint location is saved when the cRobot reaches this Tag
See inq_rob_tag_T_cRBase_idx() , inq_rob_tag_uid_cR_idx()

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto vector, maximum size KIN_DOFS

◆ inq_rob_tag_render_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_render_idx ( int  idx)
static

tag_attributes, tag render
Tag render is one of COORSYS_RENDER_STYLE_COORSYS_XYZ=0, COORSYS_RENDER_STYLE_APPROACH_Zx=1, COORSYS_RENDER_STYLE_APPROACH_Xy=2, COORSYS_RENDER_STYLE_APPROACH_Yz=3, COORSYS_RENDER_STYLE_POINT=4, COORSYS_RENDER_STYLE_INVISIBLE=5

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto tag render

◆ inq_rob_tag_speed_cp_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_speed_cp_idx ( int  idx)
static

Tag_attributes, cp speed, 0-def, [m/s]
.

// Example:
int n_path = ER_CAPI_TARGETS_PATH::inq_Get_n_paths(); // get number of pathes
int c_path = er_targets_path.inq_Get_c_path_idx(); // get cPath index
er_user_io_dialog._info_line_msg(0,"n_path %d c_path %d",n_path,c_path);
int n_tag = er_targets_path.inq_Get_n_tags(); // get number of Tags in cPath
int c_tag = er_targets_tag.inq_Get_c_tag_idx(); // get cTag index
er_user_io_dialog._info_line_msg(0,"n_tag %d c_tag %d",n_tag,c_tag);
int ok;
ok=er_targets_tag.chk_rob_tag_idx(0); // Error, 0 is an invalid tag idx, must be >= 1
ok=chk_rob_tag_idx(1); // valid if the cPath contains at least oe Tag
if (n_tag==0)
return;
char *s;
s = er_targets_tag.inq_Get_c_tag_name(); // get cTag name
if (s==NULL)
{
er_user_io_dialog._info_line_msg(0,"s NULL --> return");
return;
}
er_user_io_dialog._info_line_msg(0,"inq_Get_c_tag_name() = %s",s);
...
Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto tag speed_cp value [m/s]

◆ inq_rob_tag_speed_cp_ov_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_speed_cp_ov_idx ( int  idx)
static

Tag_attributes, cp override speed, 0-def [0-200%].

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto cp override speed

◆ inq_rob_tag_speed_ori_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_speed_ori_idx ( int  idx)
static

Tag_attributes, ori speed, 0-def, [rad/s].

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto tag ori speed value [rad/s]

◆ inq_rob_tag_speed_ori_ov_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_speed_ori_ov_idx ( int  idx)
static

Tag_attributes, ori override speed, 0-def [0-200%].

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto ori override speed

◆ inq_rob_tag_speed_ptp_ax_ov_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_speed_ptp_ax_ov_idx ( int  idx)
static

tag_attributes, ptp_ax override speed 0-def [0-200%]

Parameters
[in]idxTag index, first tag has idx = 1
Return values
ptp_axoverride speed

◆ inq_rob_tag_speed_ptp_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_speed_ptp_idx ( int  idx)
static

Tag_attributes, ptp speed, 0-def, [rad/s]
Remarks
use inq_rob_tag_speed_ptp_ov_idx() instead.

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto tag speed_ptp value [rad/s]

◆ inq_rob_tag_speed_ptp_ov_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_speed_ptp_ov_idx ( int  idx)
static

Tag_attributes, ptp override speed, 0-def [0-200%].

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto ptp override speed

◆ inq_rob_tag_T_cRBase_idx()

static ER_DllExport frame* ER_CAPI_TARGETS_TAG::inq_rob_tag_T_cRBase_idx ( int  idx)
static

Temporary Tcp location w.r.t to cRobot Base
This Tcp location w.r.t to cRobot Base is saved when the cRobot reaches this Tag
See inq_rob_tag_q_cR_idx() , inq_rob_tag_uid_cR_idx()

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto FRAME

◆ inq_rob_tag_turn_ax_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_turn_ax_idx ( int  idx)
static

tag_attributes, turn values depending on current robots turn interval
see inq_rob_tag_turn_use_idx()

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto turn value for each joint

◆ inq_rob_tag_turn_use_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_turn_use_idx ( int  idx)
static

tag_attributes, turn flag, 0-do not use turn values (def), 1-use turns
If use turns is anabled, defined turn attributes are considered
see inq_rob_tag_turn_ax_idx()

Parameters
[in]idxTag index, first tag has idx = 1
Return values
0- Do not use turn values (def)
1- Use turns

◆ inq_rob_tag_uid_cR_idx()

static ER_DllExport ER_UID* ER_CAPI_TARGETS_TAG::inq_rob_tag_uid_cR_idx ( int  idx)
static

Temporary unique robot id of cRobot
This Unique robot ID of the cRobot is saved when the cRobot reaches this Tag
See inq_rob_tag_T_cRBase_idx() , inq_rob_tag_q_cR_idx()

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto unique robot id

◆ inq_rob_tag_user_string_idx()

static ER_DllExport char* ER_CAPI_TARGETS_TAG::inq_rob_tag_user_string_idx ( int  idx)
static

tag_attributes, user defined Tag string
To store miscellaneous user data

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto user data

◆ inq_rob_tag_z_buffering_idx()

static ER_DllExport int* ER_CAPI_TARGETS_TAG::inq_rob_tag_z_buffering_idx ( int  idx)
static

tag_attributes, tag z_buffering
Tag z_buffering is one of COORSYS_Z_BUFFERING_OFF, COORSYS_Z_BUFFERING_ON

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto tag z_buffering

◆ inq_rob_tag_zone_idx()

static ER_DllExport float* ER_CAPI_TARGETS_TAG::inq_rob_tag_zone_idx ( int  idx)
static

Tag_attributes, programmed zone value [mm,%].

Parameters
[in]idxTag index, first tag has idx = 1
Return values
pointerto zone value

◆ inq_Set_tag_idx()

static ER_DllExport int ER_CAPI_TARGETS_TAG::inq_Set_tag_idx ( int  tag_idx)
static

Set current tag idx [1..n_tags] in current path.

Parameters
[in]tag_idxTag index, first tag has idx = 1
Return values
0- OK
1- invalid tag index

◆ NewTagOnFrame()

static ER_DllExport int ER_CAPI_TARGETS_TAG::NewTagOnFrame ( frame T)
static

Creates a new Tag in current path at location of frame 'T',
without grf_update and TagDlg update.

Parameters
[in]Tlocation w.r.t. work object, FRAME
Return values
0- OK
1- cannot create new tag

◆ NewTagOnFrame_update()

static ER_DllExport int ER_CAPI_TARGETS_TAG::NewTagOnFrame_update ( frame T,
int  update_mode 
)
static

Creates a new Tag in current path at location of frame 'T'
Parameter is a bitwise inclusive OR operator (|) of.

  • 0x1 : updates 3D-Scenario
  • 0x2 : updates TagWindow
    Parameters
    [in]Tlocation w.r.t. work object, FRAME
    [in]update_mode- updates 3D-Scenario and TagWindow
    Return values
    0- OK
    1- cannot create new tag

◆ NewTagOnPickPoint()

static ER_DllExport int ER_CAPI_TARGETS_TAG::NewTagOnPickPoint ( int  vertices = 0)
static

Creates a new Tag at current picked location
If vertices = 1 : keep cOrientation
If vertices = 0 : use polygon normal for approach direction.

Parameters
[in]vertices
Return values
0- OK
1- cannot create new tag

◆ NewTagOnTcp()

static ER_DllExport int ER_CAPI_TARGETS_TAG::NewTagOnTcp ( void  )
static

Creates a new Tag in current path at Tcp of cRobot.

Return values
0- OK
1- cannot create a new Tag

◆ Shift_cTagOnFrame()

static ER_DllExport int ER_CAPI_TARGETS_TAG::Shift_cTagOnFrame ( frame T)
static

Shifts cTag to location of frame 'T'.

Parameters
[in]Tlocation w.r.t. work object, FRAME
Return values
0- OK
1- cannot shift tag

◆ Shift_cTagOnPickPoint()

static ER_DllExport int ER_CAPI_TARGETS_TAG::Shift_cTagOnPickPoint ( int  vertices = 0)
static

Shifts cTag to the current picked location
If vertices = 1 : keep cOrientation
If vertices = 0 : use polygon normal for approach direction.

Parameters
[in]vertices
Return values
0- OK
1- cannot shift cTag

◆ Shift_cTagOnTcp()

static ER_DllExport int ER_CAPI_TARGETS_TAG::Shift_cTagOnTcp ( void  )
static

Shifts cTag to the Tcp of cRobot
The cTag will jump to the cRobot Tcp.

Return values
0- OK
1- cannot shift tag

◆ swap_TagDown()

static ER_DllExport int ER_CAPI_TARGETS_TAG::swap_TagDown ( void  )
static

Swaps Tag pointer with the next Tag
.

Return values
0- OK
1- cannot swap tag

◆ swap_TagUp()

static ER_DllExport int ER_CAPI_TARGETS_TAG::swap_TagUp ( void  )
static

Swaps Tag pointer with the prev Tag.

Return values
0- OK
1- cannot swap tag

◆ TagClone()

static ER_DllExport void ER_CAPI_TARGETS_TAG::TagClone ( void  )
static

Multiple clone of current Tag
Clone all selected Tags.

Return values
void

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